From 5710bc19e868e8dce5daf7a766b757c391576ed2 Mon Sep 17 00:00:00 2001 From: wangziyang <2890199310@qq.com> Date: Thu, 12 May 2022 19:59:27 +0800 Subject: [PATCH] =?UTF-8?q?=E6=8F=90=E4=BA=A4=E6=BA=90=E7=A0=81?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- src/Search_2D/.idea/.gitignore | 3 + src/Search_2D/.idea/Search_2D.iml | 12 + .../inspectionProfiles/Project_Default.xml | 15 + .../inspectionProfiles/profiles_settings.xml | 6 + src/Search_2D/.idea/misc.xml | 4 + src/Search_2D/.idea/modules.xml | 8 + src/Search_2D/ARAstar.py | 222 ++++++++++++ src/Search_2D/Anytime_D_star.py | 317 ++++++++++++++++++ src/Search_2D/Astar.py | 224 +++++++++++++ src/Search_2D/Best_First.py | 68 ++++ src/Search_2D/Bidirectional_a_star.py | 229 +++++++++++++ src/Search_2D/D_star.py | 304 +++++++++++++++++ src/Search_2D/D_star_Lite.py | 239 +++++++++++++ src/Search_2D/Dijkstra.py | 69 ++++ src/Search_2D/LPAstar.py | 256 ++++++++++++++ src/Search_2D/LRTAstar.py | 230 +++++++++++++ src/Search_2D/RTAAStar.py | 237 +++++++++++++ .../__pycache__/Astar.cpython-38.pyc | Bin 0 -> 5495 bytes src/Search_2D/__pycache__/env.cpython-37.pyc | Bin 0 -> 1434 bytes src/Search_2D/__pycache__/env.cpython-38.pyc | Bin 0 -> 1405 bytes src/Search_2D/__pycache__/env.cpython-39.pyc | Bin 0 -> 1397 bytes .../__pycache__/plotting.cpython-37.pyc | Bin 0 -> 5340 bytes .../__pycache__/plotting.cpython-38.pyc | Bin 0 -> 5398 bytes .../__pycache__/plotting.cpython-39.pyc | Bin 0 -> 5332 bytes .../__pycache__/queue.cpython-37.pyc | Bin 0 -> 2672 bytes .../__pycache__/queue.cpython-38.pyc | Bin 0 -> 2668 bytes src/Search_2D/bfs.py | 69 ++++ src/Search_2D/dfs.py | 65 ++++ src/Search_2D/env.py | 52 +++ src/Search_2D/plotting.py | 165 +++++++++ src/Search_2D/queue.py | 62 ++++ src/Tello/KeyPress.py | 19 ++ src/Tello/KeyPressModule.py | 31 ++ src/Tello/KeyboardControl.py | 105 ++++++ src/Tello/__pycache__/KeyPress.cpython-39.pyc | Bin 0 -> 564 bytes .../__pycache__/KeyPressModule.cpython-39.pyc | Bin 0 -> 657 bytes .../KeyboardControl.cpython-39.pyc | Bin 0 -> 2022 bytes src/prepare/calculate.py | 12 + src/prepare/change_file.py | 84 +++++ src/prepare/spider.py | 5 + src/qt/__pycache__/page1.cpython-39.pyc | Bin 0 -> 4957 bytes src/qt/__pycache__/page2.cpython-39.pyc | Bin 0 -> 8353 bytes src/qt/__pycache__/tello_UI.cpython-39.pyc | Bin 0 -> 3041 bytes src/qt/__pycache__/vedio_demo.cpython-39.pyc | Bin 0 -> 1798 bytes src/qt/page1.py | 114 +++++++ src/qt/page2.py | 280 ++++++++++++++++ src/qt/system_main.py | 96 ++++++ src/qt/tello_UI.py | 97 ++++++ src/qt/tello_png/jiangluo.png | Bin 0 -> 62321 bytes src/qt/tello_png/left.png | Bin 0 -> 18119 bytes src/qt/tello_png/qifei.png | Bin 0 -> 56861 bytes src/qt/tello_png/return.png | Bin 0 -> 20994 bytes src/qt/tello_png/right.png | Bin 0 -> 19202 bytes src/qt/tello_png/up.png | Bin 0 -> 18053 bytes src/qt/vedio_demo.py | 50 +++ 55 files changed, 3749 insertions(+) create mode 100644 src/Search_2D/.idea/.gitignore create mode 100644 src/Search_2D/.idea/Search_2D.iml create mode 100644 src/Search_2D/.idea/inspectionProfiles/Project_Default.xml create mode 100644 src/Search_2D/.idea/inspectionProfiles/profiles_settings.xml create mode 100644 src/Search_2D/.idea/misc.xml create mode 100644 src/Search_2D/.idea/modules.xml create mode 100644 src/Search_2D/ARAstar.py create mode 100644 src/Search_2D/Anytime_D_star.py create mode 100644 src/Search_2D/Astar.py create mode 100644 src/Search_2D/Best_First.py create mode 100644 src/Search_2D/Bidirectional_a_star.py create mode 100644 src/Search_2D/D_star.py create mode 100644 src/Search_2D/D_star_Lite.py create mode 100644 src/Search_2D/Dijkstra.py create mode 100644 src/Search_2D/LPAstar.py create mode 100644 src/Search_2D/LRTAstar.py create mode 100644 src/Search_2D/RTAAStar.py create mode 100644 src/Search_2D/__pycache__/Astar.cpython-38.pyc create mode 100644 src/Search_2D/__pycache__/env.cpython-37.pyc create mode 100644 src/Search_2D/__pycache__/env.cpython-38.pyc create mode 100644 src/Search_2D/__pycache__/env.cpython-39.pyc create mode 100644 src/Search_2D/__pycache__/plotting.cpython-37.pyc create mode 100644 src/Search_2D/__pycache__/plotting.cpython-38.pyc create mode 100644 src/Search_2D/__pycache__/plotting.cpython-39.pyc create mode 100644 src/Search_2D/__pycache__/queue.cpython-37.pyc create mode 100644 src/Search_2D/__pycache__/queue.cpython-38.pyc create mode 100644 src/Search_2D/bfs.py create mode 100644 src/Search_2D/dfs.py create mode 100644 src/Search_2D/env.py create mode 100644 src/Search_2D/plotting.py create mode 100644 src/Search_2D/queue.py create mode 100644 src/Tello/KeyPress.py create mode 100644 src/Tello/KeyPressModule.py create mode 100644 src/Tello/KeyboardControl.py create mode 100644 src/Tello/__pycache__/KeyPress.cpython-39.pyc create mode 100644 src/Tello/__pycache__/KeyPressModule.cpython-39.pyc create mode 100644 src/Tello/__pycache__/KeyboardControl.cpython-39.pyc create mode 100644 src/prepare/calculate.py create mode 100644 src/prepare/change_file.py create mode 100644 src/prepare/spider.py create mode 100644 src/qt/__pycache__/page1.cpython-39.pyc create mode 100644 src/qt/__pycache__/page2.cpython-39.pyc create mode 100644 src/qt/__pycache__/tello_UI.cpython-39.pyc create mode 100644 src/qt/__pycache__/vedio_demo.cpython-39.pyc create mode 100644 src/qt/page1.py create mode 100644 src/qt/page2.py create mode 100644 src/qt/system_main.py create mode 100644 src/qt/tello_UI.py create mode 100644 src/qt/tello_png/jiangluo.png create mode 100644 src/qt/tello_png/left.png create mode 100644 src/qt/tello_png/qifei.png create mode 100644 src/qt/tello_png/return.png create mode 100644 src/qt/tello_png/right.png create mode 100644 src/qt/tello_png/up.png create mode 100644 src/qt/vedio_demo.py diff --git a/src/Search_2D/.idea/.gitignore b/src/Search_2D/.idea/.gitignore new file mode 100644 index 0000000..359bb53 --- /dev/null +++ b/src/Search_2D/.idea/.gitignore @@ -0,0 +1,3 @@ +# 默认忽略的文件 +/shelf/ +/workspace.xml diff --git a/src/Search_2D/.idea/Search_2D.iml b/src/Search_2D/.idea/Search_2D.iml new file mode 100644 index 0000000..8b8c395 --- /dev/null +++ b/src/Search_2D/.idea/Search_2D.iml @@ -0,0 +1,12 @@ + + + + + + + + + + \ No newline at end of file diff --git a/src/Search_2D/.idea/inspectionProfiles/Project_Default.xml b/src/Search_2D/.idea/inspectionProfiles/Project_Default.xml new file mode 100644 index 0000000..6736707 --- /dev/null +++ b/src/Search_2D/.idea/inspectionProfiles/Project_Default.xml @@ -0,0 +1,15 @@ + + + + \ No newline at end of file diff --git a/src/Search_2D/.idea/inspectionProfiles/profiles_settings.xml b/src/Search_2D/.idea/inspectionProfiles/profiles_settings.xml new file mode 100644 index 0000000..105ce2d --- /dev/null +++ b/src/Search_2D/.idea/inspectionProfiles/profiles_settings.xml @@ -0,0 +1,6 @@ + + + + \ No newline at end of file diff --git a/src/Search_2D/.idea/misc.xml b/src/Search_2D/.idea/misc.xml new file mode 100644 index 0000000..d56657a --- /dev/null +++ b/src/Search_2D/.idea/misc.xml @@ -0,0 +1,4 @@ + + + + \ No newline at end of file diff --git a/src/Search_2D/.idea/modules.xml b/src/Search_2D/.idea/modules.xml new file mode 100644 index 0000000..01049a7 --- /dev/null +++ b/src/Search_2D/.idea/modules.xml @@ -0,0 +1,8 @@ + + + + + + + + \ No newline at end of file diff --git a/src/Search_2D/ARAstar.py b/src/Search_2D/ARAstar.py new file mode 100644 index 0000000..c014616 --- /dev/null +++ b/src/Search_2D/ARAstar.py @@ -0,0 +1,222 @@ +""" +ARA_star 2D (Anytime Repairing A*) +@author: huiming zhou + +@description: local inconsistency: g-value decreased. +g(s) decreased introduces a local inconsistency between s and its successors. + +""" + +import os +import sys +import math + +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../../Search_based_Planning/") + +from Search_2D import plotting, env + + +class AraStar: + def __init__(self, s_start, s_goal, e, heuristic_type): + self.s_start, self.s_goal = s_start, s_goal + self.heuristic_type = heuristic_type + + self.Env = env.Env() # class Env + + self.u_set = self.Env.motions # feasible input set + self.obs = self.Env.obs # position of obstacles + self.e = e # weight + + self.g = dict() # Cost to come + self.OPEN = dict() # priority queue / OPEN set + self.CLOSED = set() # CLOSED set + self.INCONS = {} # INCONSISTENT set + self.PARENT = dict() # relations + self.path = [] # planning path + self.visited = [] # order of visited nodes + + def init(self): + """ + initialize each set. + """ + + self.g[self.s_start] = 0.0 + self.g[self.s_goal] = math.inf + self.OPEN[self.s_start] = self.f_value(self.s_start) + self.PARENT[self.s_start] = self.s_start + + def searching(self): + self.init() + self.ImprovePath() + self.path.append(self.extract_path()) + + while self.update_e() > 1: # continue condition + self.e -= 0.4 # increase weight + self.OPEN.update(self.INCONS) + self.OPEN = {s: self.f_value(s) for s in self.OPEN} # update f_value of OPEN set + + self.INCONS = dict() + self.CLOSED = set() + self.ImprovePath() # improve path + self.path.append(self.extract_path()) + + return self.path, self.visited + + def ImprovePath(self): + """ + :return: a e'-suboptimal path + """ + + visited_each = [] + + while True: + s, f_small = self.calc_smallest_f() + + if self.f_value(self.s_goal) <= f_small: + break + + self.OPEN.pop(s) + self.CLOSED.add(s) + + for s_n in self.get_neighbor(s): + if s_n in self.obs: + continue + + new_cost = self.g[s] + self.cost(s, s_n) + + if s_n not in self.g or new_cost < self.g[s_n]: + self.g[s_n] = new_cost + self.PARENT[s_n] = s + visited_each.append(s_n) + + if s_n not in self.CLOSED: + self.OPEN[s_n] = self.f_value(s_n) + else: + self.INCONS[s_n] = 0.0 + + self.visited.append(visited_each) + + def calc_smallest_f(self): + """ + :return: node with smallest f_value in OPEN set. + """ + + s_small = min(self.OPEN, key=self.OPEN.get) + + return s_small, self.OPEN[s_small] + + def get_neighbor(self, s): + """ + find neighbors of state s that not in obstacles. + :param s: state + :return: neighbors + """ + + return {(s[0] + u[0], s[1] + u[1]) for u in self.u_set} + + def update_e(self): + v = float("inf") + + if self.OPEN: + v = min(self.g[s] + self.h(s) for s in self.OPEN) + if self.INCONS: + v = min(v, min(self.g[s] + self.h(s) for s in self.INCONS)) + + return min(self.e, self.g[self.s_goal] / v) + + def f_value(self, x): + """ + f = g + e * h + f = cost-to-come + weight * cost-to-go + :param x: current state + :return: f_value + """ + + return self.g[x] + self.e * self.h(x) + + def extract_path(self): + """ + Extract the path based on the PARENT set. + :return: The planning path + """ + + path = [self.s_goal] + s = self.s_goal + + while True: + s = self.PARENT[s] + path.append(s) + + if s == self.s_start: + break + + return list(path) + + def h(self, s): + """ + Calculate heuristic. + :param s: current node (state) + :return: heuristic function value + """ + + heuristic_type = self.heuristic_type # heuristic type + goal = self.s_goal # goal node + + if heuristic_type == "manhattan": + return abs(goal[0] - s[0]) + abs(goal[1] - s[1]) + else: + return math.hypot(goal[0] - s[0], goal[1] - s[1]) + + def cost(self, s_start, s_goal): + """ + Calculate Cost for this motion + :param s_start: starting node + :param s_goal: end node + :return: Cost for this motion + :note: Cost function could be more complicate! + """ + + if self.is_collision(s_start, s_goal): + return math.inf + + return math.hypot(s_goal[0] - s_start[0], s_goal[1] - s_start[1]) + + def is_collision(self, s_start, s_end): + """ + check if the line segment (s_start, s_end) is collision. + :param s_start: start node + :param s_end: end node + :return: True: is collision / False: not collision + """ + + if s_start in self.obs or s_end in self.obs: + return True + + if s_start[0] != s_end[0] and s_start[1] != s_end[1]: + if s_end[0] - s_start[0] == s_start[1] - s_end[1]: + s1 = (min(s_start[0], s_end[0]), min(s_start[1], s_end[1])) + s2 = (max(s_start[0], s_end[0]), max(s_start[1], s_end[1])) + else: + s1 = (min(s_start[0], s_end[0]), max(s_start[1], s_end[1])) + s2 = (max(s_start[0], s_end[0]), min(s_start[1], s_end[1])) + + if s1 in self.obs or s2 in self.obs: + return True + + return False + + +def main(): + s_start = (5, 5) + s_goal = (45, 25) + + arastar = AraStar(s_start, s_goal, 2.5, "euclidean") + plot = plotting.Plotting(s_start, s_goal) + + path, visited = arastar.searching() + plot.animation_ara_star(path, visited, "Anytime Repairing A* (ARA*)") + + +if __name__ == '__main__': + main() diff --git a/src/Search_2D/Anytime_D_star.py b/src/Search_2D/Anytime_D_star.py new file mode 100644 index 0000000..cd1d62b --- /dev/null +++ b/src/Search_2D/Anytime_D_star.py @@ -0,0 +1,317 @@ +""" +Anytime_D_star 2D +@author: huiming zhou +""" + +import os +import sys +import math +import matplotlib.pyplot as plt + +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../../Search_based_Planning/") + +from Search_2D import plotting +from Search_2D import env + + +class ADStar: + def __init__(self, s_start, s_goal, eps, heuristic_type): + self.s_start, self.s_goal = s_start, s_goal + self.heuristic_type = heuristic_type + + self.Env = env.Env() # class Env + self.Plot = plotting.Plotting(s_start, s_goal) + + self.u_set = self.Env.motions # feasible input set + self.obs = self.Env.obs # position of obstacles + self.x = self.Env.x_range + self.y = self.Env.y_range + + self.g, self.rhs, self.OPEN = {}, {}, {} + + for i in range(1, self.Env.x_range - 1): + for j in range(1, self.Env.y_range - 1): + self.rhs[(i, j)] = float("inf") + self.g[(i, j)] = float("inf") + + self.rhs[self.s_goal] = 0.0 + self.eps = eps + self.OPEN[self.s_goal] = self.Key(self.s_goal) + self.CLOSED, self.INCONS = set(), dict() + + self.visited = set() + self.count = 0 + self.count_env_change = 0 + self.obs_add = set() + self.obs_remove = set() + self.title = "Anytime D*: Small changes" # Significant changes + self.fig = plt.figure() + + def run(self): + self.Plot.plot_grid(self.title) + self.ComputeOrImprovePath() + self.plot_visited() + self.plot_path(self.extract_path()) + self.visited = set() + + while True: + if self.eps <= 1.0: + break + self.eps -= 0.5 + self.OPEN.update(self.INCONS) + for s in self.OPEN: + self.OPEN[s] = self.Key(s) + self.CLOSED = set() + self.ComputeOrImprovePath() + self.plot_visited() + self.plot_path(self.extract_path()) + self.visited = set() + plt.pause(0.5) + + self.fig.canvas.mpl_connect('button_press_event', self.on_press) + plt.show() + + def on_press(self, event): + x, y = event.xdata, event.ydata + if x < 0 or x > self.x - 1 or y < 0 or y > self.y - 1: + print("Please choose right area!") + else: + self.count_env_change += 1 + x, y = int(x), int(y) + print("Change position: s =", x, ",", "y =", y) + + # for small changes + if self.title == "Anytime D*: Small changes": + if (x, y) not in self.obs: + self.obs.add((x, y)) + self.g[(x, y)] = float("inf") + self.rhs[(x, y)] = float("inf") + else: + self.obs.remove((x, y)) + self.UpdateState((x, y)) + + self.Plot.update_obs(self.obs) + + for sn in self.get_neighbor((x, y)): + self.UpdateState(sn) + + plt.cla() + self.Plot.plot_grid(self.title) + + while True: + if len(self.INCONS) == 0: + break + self.OPEN.update(self.INCONS) + for s in self.OPEN: + self.OPEN[s] = self.Key(s) + self.CLOSED = set() + self.ComputeOrImprovePath() + self.plot_visited() + self.plot_path(self.extract_path()) + # plt.plot(self.title) + self.visited = set() + + if self.eps <= 1.0: + break + + else: + if (x, y) not in self.obs: + self.obs.add((x, y)) + self.obs_add.add((x, y)) + plt.plot(x, y, 'sk') + if (x, y) in self.obs_remove: + self.obs_remove.remove((x, y)) + else: + self.obs.remove((x, y)) + self.obs_remove.add((x, y)) + plt.plot(x, y, marker='s', color='white') + if (x, y) in self.obs_add: + self.obs_add.remove((x, y)) + + self.Plot.update_obs(self.obs) + + if self.count_env_change >= 15: + self.count_env_change = 0 + self.eps += 2.0 + for s in self.obs_add: + self.g[(x, y)] = float("inf") + self.rhs[(x, y)] = float("inf") + + for sn in self.get_neighbor(s): + self.UpdateState(sn) + + for s in self.obs_remove: + for sn in self.get_neighbor(s): + self.UpdateState(sn) + self.UpdateState(s) + + plt.cla() + self.Plot.plot_grid(self.title) + + while True: + if self.eps <= 1.0: + break + self.eps -= 0.5 + self.OPEN.update(self.INCONS) + for s in self.OPEN: + self.OPEN[s] = self.Key(s) + self.CLOSED = set() + self.ComputeOrImprovePath() + self.plot_visited() + self.plot_path(self.extract_path()) + plt.title(self.title) + self.visited = set() + plt.pause(0.5) + + self.fig.canvas.draw_idle() + + def ComputeOrImprovePath(self): + while True: + s, v = self.TopKey() + if v >= self.Key(self.s_start) and \ + self.rhs[self.s_start] == self.g[self.s_start]: + break + + self.OPEN.pop(s) + self.visited.add(s) + + if self.g[s] > self.rhs[s]: + self.g[s] = self.rhs[s] + self.CLOSED.add(s) + for sn in self.get_neighbor(s): + self.UpdateState(sn) + else: + self.g[s] = float("inf") + for sn in self.get_neighbor(s): + self.UpdateState(sn) + self.UpdateState(s) + + def UpdateState(self, s): + if s != self.s_goal: + self.rhs[s] = float("inf") + for x in self.get_neighbor(s): + self.rhs[s] = min(self.rhs[s], self.g[x] + self.cost(s, x)) + if s in self.OPEN: + self.OPEN.pop(s) + + if self.g[s] != self.rhs[s]: + if s not in self.CLOSED: + self.OPEN[s] = self.Key(s) + else: + self.INCONS[s] = 0 + + def Key(self, s): + if self.g[s] > self.rhs[s]: + return [self.rhs[s] + self.eps * self.h(self.s_start, s), self.rhs[s]] + else: + return [self.g[s] + self.h(self.s_start, s), self.g[s]] + + def TopKey(self): + """ + :return: return the min key and its value. + """ + + s = min(self.OPEN, key=self.OPEN.get) + return s, self.OPEN[s] + + def h(self, s_start, s_goal): + heuristic_type = self.heuristic_type # heuristic type + + if heuristic_type == "manhattan": + return abs(s_goal[0] - s_start[0]) + abs(s_goal[1] - s_start[1]) + else: + return math.hypot(s_goal[0] - s_start[0], s_goal[1] - s_start[1]) + + def cost(self, s_start, s_goal): + """ + Calculate Cost for this motion + :param s_start: starting node + :param s_goal: end node + :return: Cost for this motion + :note: Cost function could be more complicate! + """ + + if self.is_collision(s_start, s_goal): + return float("inf") + + return math.hypot(s_goal[0] - s_start[0], s_goal[1] - s_start[1]) + + def is_collision(self, s_start, s_end): + if s_start in self.obs or s_end in self.obs: + return True + + if s_start[0] != s_end[0] and s_start[1] != s_end[1]: + if s_end[0] - s_start[0] == s_start[1] - s_end[1]: + s1 = (min(s_start[0], s_end[0]), min(s_start[1], s_end[1])) + s2 = (max(s_start[0], s_end[0]), max(s_start[1], s_end[1])) + else: + s1 = (min(s_start[0], s_end[0]), max(s_start[1], s_end[1])) + s2 = (max(s_start[0], s_end[0]), min(s_start[1], s_end[1])) + + if s1 in self.obs or s2 in self.obs: + return True + + return False + + def get_neighbor(self, s): + nei_list = set() + for u in self.u_set: + s_next = tuple([s[i] + u[i] for i in range(2)]) + if s_next not in self.obs: + nei_list.add(s_next) + + return nei_list + + def extract_path(self): + """ + Extract the path based on the PARENT set. + :return: The planning path + """ + + path = [self.s_start] + s = self.s_start + + for k in range(100): + g_list = {} + for x in self.get_neighbor(s): + if not self.is_collision(s, x): + g_list[x] = self.g[x] + s = min(g_list, key=g_list.get) + path.append(s) + if s == self.s_goal: + break + + return list(path) + + def plot_path(self, path): + px = [x[0] for x in path] + py = [x[1] for x in path] + plt.plot(px, py, linewidth=2) + plt.plot(self.s_start[0], self.s_start[1], "bs") + plt.plot(self.s_goal[0], self.s_goal[1], "gs") + + def plot_visited(self): + self.count += 1 + + color = ['gainsboro', 'lightgray', 'silver', 'darkgray', + 'bisque', 'navajowhite', 'moccasin', 'wheat', + 'powderblue', 'skyblue', 'lightskyblue', 'cornflowerblue'] + + if self.count >= len(color) - 1: + self.count = 0 + + for x in self.visited: + plt.plot(x[0], x[1], marker='s', color=color[self.count]) + + +def main(): + s_start = (5, 5) + s_goal = (45, 25) + + dstar = ADStar(s_start, s_goal, 2.5, "euclidean") + dstar.run() + + +if __name__ == '__main__': + main() diff --git a/src/Search_2D/Astar.py b/src/Search_2D/Astar.py new file mode 100644 index 0000000..3c8e554 --- /dev/null +++ b/src/Search_2D/Astar.py @@ -0,0 +1,224 @@ +""" +A_star 2D +@author: huiming zhou +""" + +import os +import sys +import math +import heapq + +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../../PaddleClas-release-2.3") + +from Search_2D import plotting, env + + +class AStar: + """AStar set the cost + heuristics as the priority + """ + def __init__(self, s_start, s_goal, heuristic_type): + self.s_start = s_start + self.s_goal = s_goal + self.heuristic_type = heuristic_type + + self.Env = env.Env() # class Env + + self.u_set = self.Env.motions # feasible input set + self.obs = self.Env.obs # position of obstacles + + self.OPEN = [] # priority queue / OPEN set + self.CLOSED = [] # CLOSED set / VISITED order + self.PARENT = dict() # recorded parent + self.g = dict() # cost to come + + def searching(self): + """ + A_star Searching. + :return: path, visited order + """ + + self.PARENT[self.s_start] = self.s_start + self.g[self.s_start] = 0 + self.g[self.s_goal] = math.inf + heapq.heappush(self.OPEN, + (self.f_value(self.s_start), self.s_start)) + + while self.OPEN: + _, s = heapq.heappop(self.OPEN) + self.CLOSED.append(s) + + if s == self.s_goal: # stop condition + break + + for s_n in self.get_neighbor(s): + new_cost = self.g[s] + self.cost(s, s_n) + + if s_n not in self.g: + self.g[s_n] = math.inf + + if new_cost < self.g[s_n]: # conditions for updating Cost + self.g[s_n] = new_cost + self.PARENT[s_n] = s + heapq.heappush(self.OPEN, (self.f_value(s_n), s_n)) + + return self.extract_path(self.PARENT), self.CLOSED + + def searching_repeated_astar(self, e): + """ + repeated A*. + :param e: weight of A* + :return: path and visited order + """ + + path, visited = [], [] + + while e >= 1: + p_k, v_k = self.repeated_searching(self.s_start, self.s_goal, e) + path.append(p_k) + visited.append(v_k) + e -= 0.5 + + return path, visited + + def repeated_searching(self, s_start, s_goal, e): + """ + run A* with weight e. + :param s_start: starting state + :param s_goal: goal state + :param e: weight of a* + :return: path and visited order. + """ + + g = {s_start: 0, s_goal: float("inf")} + PARENT = {s_start: s_start} + OPEN = [] + CLOSED = [] + heapq.heappush(OPEN, + (g[s_start] + e * self.heuristic(s_start), s_start)) + + while OPEN: + _, s = heapq.heappop(OPEN) + CLOSED.append(s) + + if s == s_goal: + break + + for s_n in self.get_neighbor(s): + new_cost = g[s] + self.cost(s, s_n) + + if s_n not in g: + g[s_n] = math.inf + + if new_cost < g[s_n]: # conditions for updating Cost + g[s_n] = new_cost + PARENT[s_n] = s + heapq.heappush(OPEN, (g[s_n] + e * self.heuristic(s_n), s_n)) + + return self.extract_path(PARENT), CLOSED + + def get_neighbor(self, s): + """ + find neighbors of state s that not in obstacles. + :param s: state + :return: neighbors + """ + + return [(s[0] + u[0], s[1] + u[1]) for u in self.u_set] + + def cost(self, s_start, s_goal): + """ + Calculate Cost for this motion + :param s_start: starting node + :param s_goal: end node + :return: Cost for this motion + :note: Cost function could be more complicate! + """ + + if self.is_collision(s_start, s_goal): + return math.inf + + return math.hypot(s_goal[0] - s_start[0], s_goal[1] - s_start[1]) + + def is_collision(self, s_start, s_end): + """ + check if the line segment (s_start, s_end) is collision. + :param s_start: start node + :param s_end: end node + :return: True: is collision / False: not collision + """ + + if s_start in self.obs or s_end in self.obs: + return True + + if s_start[0] != s_end[0] and s_start[1] != s_end[1]: + if s_end[0] - s_start[0] == s_start[1] - s_end[1]: + s1 = (min(s_start[0], s_end[0]), min(s_start[1], s_end[1])) + s2 = (max(s_start[0], s_end[0]), max(s_start[1], s_end[1])) + else: + s1 = (min(s_start[0], s_end[0]), max(s_start[1], s_end[1])) + s2 = (max(s_start[0], s_end[0]), min(s_start[1], s_end[1])) + + if s1 in self.obs or s2 in self.obs: + return True + + return False + + def f_value(self, s): + """ + f = g + h. (g: Cost to come, h: heuristic value) + :param s: current state + :return: f + """ + + return self.g[s] + self.heuristic(s) + + def extract_path(self, PARENT): + """ + Extract the path based on the PARENT set. + :return: The planning path + """ + + path = [self.s_goal] + s = self.s_goal + + while True: + s = PARENT[s] + path.append(s) + + if s == self.s_start: + break + + return list(path) + + def heuristic(self, s): + """ + Calculate heuristic. + :param s: current node (state) + :return: heuristic function value + """ + + heuristic_type = self.heuristic_type # heuristic type + goal = self.s_goal # goal node + + if heuristic_type == "manhattan": + return abs(goal[0] - s[0]) + abs(goal[1] - s[1]) + else: + return math.hypot(goal[0] - s[0], goal[1] - s[1]) + + +def main(): + s_start = (5, 5) + s_goal = (45, 25) + + astar = AStar(s_start, s_goal, "euclidean") + plot = plotting.Plotting(s_start, s_goal) + + path, visited = astar.searching() + plot.animation(path, visited, "A*") # animation + + # path, visited = astar.searching_repeated_astar(2.5) # initial weight e = 2.5 + # plot.animation_ara_star(path, visited, "Repeated A*") + + +if __name__ == '__main__': + main() diff --git a/src/Search_2D/Best_First.py b/src/Search_2D/Best_First.py new file mode 100644 index 0000000..0c85fba --- /dev/null +++ b/src/Search_2D/Best_First.py @@ -0,0 +1,68 @@ +""" +Best-First Searching +@author: huiming zhou +""" + +import os +import sys +import math +import heapq + +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../../Search_based_Planning/") + +from Search_2D import plotting, env +from Search_2D.Astar import AStar + + +class BestFirst(AStar): + """BestFirst set the heuristics as the priority + """ + def searching(self): + """ + Breadth-first Searching. + :return: path, visited order + """ + + self.PARENT[self.s_start] = self.s_start + self.g[self.s_start] = 0 + self.g[self.s_goal] = math.inf + heapq.heappush(self.OPEN, + (self.heuristic(self.s_start), self.s_start)) + + while self.OPEN: + _, s = heapq.heappop(self.OPEN) + self.CLOSED.append(s) + + if s == self.s_goal: + break + + for s_n in self.get_neighbor(s): + new_cost = self.g[s] + self.cost(s, s_n) + + if s_n not in self.g: + self.g[s_n] = math.inf + + if new_cost < self.g[s_n]: # conditions for updating Cost + self.g[s_n] = new_cost + self.PARENT[s_n] = s + + # best first set the heuristics as the priority + heapq.heappush(self.OPEN, (self.heuristic(s_n), s_n)) + + return self.extract_path(self.PARENT), self.CLOSED + + +def main(): + s_start = (5, 5) + s_goal = (45, 25) + + BF = BestFirst(s_start, s_goal, 'euclidean') + plot = plotting.Plotting(s_start, s_goal) + + path, visited = BF.searching() + plot.animation(path, visited, "Best-first Searching") # animation + + +if __name__ == '__main__': + main() diff --git a/src/Search_2D/Bidirectional_a_star.py b/src/Search_2D/Bidirectional_a_star.py new file mode 100644 index 0000000..3580c1a --- /dev/null +++ b/src/Search_2D/Bidirectional_a_star.py @@ -0,0 +1,229 @@ +""" +Bidirectional_a_star 2D +@author: huiming zhou +""" + +import os +import sys +import math +import heapq + +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../../Search_based_Planning/") + +from Search_2D import plotting, env + + +class BidirectionalAStar: + def __init__(self, s_start, s_goal, heuristic_type): + self.s_start = s_start + self.s_goal = s_goal + self.heuristic_type = heuristic_type + + self.Env = env.Env() # class Env + + self.u_set = self.Env.motions # feasible input set + self.obs = self.Env.obs # position of obstacles + + self.OPEN_fore = [] # OPEN set for forward searching + self.OPEN_back = [] # OPEN set for backward searching + self.CLOSED_fore = [] # CLOSED set for forward + self.CLOSED_back = [] # CLOSED set for backward + self.PARENT_fore = dict() # recorded parent for forward + self.PARENT_back = dict() # recorded parent for backward + self.g_fore = dict() # cost to come for forward + self.g_back = dict() # cost to come for backward + + def init(self): + """ + initialize parameters + """ + + self.g_fore[self.s_start] = 0.0 + self.g_fore[self.s_goal] = math.inf + self.g_back[self.s_goal] = 0.0 + self.g_back[self.s_start] = math.inf + self.PARENT_fore[self.s_start] = self.s_start + self.PARENT_back[self.s_goal] = self.s_goal + heapq.heappush(self.OPEN_fore, + (self.f_value_fore(self.s_start), self.s_start)) + heapq.heappush(self.OPEN_back, + (self.f_value_back(self.s_goal), self.s_goal)) + + def searching(self): + """ + Bidirectional A* + :return: connected path, visited order of forward, visited order of backward + """ + + self.init() + s_meet = self.s_start + + while self.OPEN_fore and self.OPEN_back: + # solve foreward-search + _, s_fore = heapq.heappop(self.OPEN_fore) + + if s_fore in self.PARENT_back: + s_meet = s_fore + break + + self.CLOSED_fore.append(s_fore) + + for s_n in self.get_neighbor(s_fore): + new_cost = self.g_fore[s_fore] + self.cost(s_fore, s_n) + + if s_n not in self.g_fore: + self.g_fore[s_n] = math.inf + + if new_cost < self.g_fore[s_n]: + self.g_fore[s_n] = new_cost + self.PARENT_fore[s_n] = s_fore + heapq.heappush(self.OPEN_fore, + (self.f_value_fore(s_n), s_n)) + + # solve backward-search + _, s_back = heapq.heappop(self.OPEN_back) + + if s_back in self.PARENT_fore: + s_meet = s_back + break + + self.CLOSED_back.append(s_back) + + for s_n in self.get_neighbor(s_back): + new_cost = self.g_back[s_back] + self.cost(s_back, s_n) + + if s_n not in self.g_back: + self.g_back[s_n] = math.inf + + if new_cost < self.g_back[s_n]: + self.g_back[s_n] = new_cost + self.PARENT_back[s_n] = s_back + heapq.heappush(self.OPEN_back, + (self.f_value_back(s_n), s_n)) + + return self.extract_path(s_meet), self.CLOSED_fore, self.CLOSED_back + + def get_neighbor(self, s): + """ + find neighbors of state s that not in obstacles. + :param s: state + :return: neighbors + """ + + return [(s[0] + u[0], s[1] + u[1]) for u in self.u_set] + + def extract_path(self, s_meet): + """ + extract path from start and goal + :param s_meet: meet point of bi-direction a* + :return: path + """ + + # extract path for foreward part + path_fore = [s_meet] + s = s_meet + + while True: + s = self.PARENT_fore[s] + path_fore.append(s) + if s == self.s_start: + break + + # extract path for backward part + path_back = [] + s = s_meet + + while True: + s = self.PARENT_back[s] + path_back.append(s) + if s == self.s_goal: + break + + return list(reversed(path_fore)) + list(path_back) + + def f_value_fore(self, s): + """ + forward searching: f = g + h. (g: Cost to come, h: heuristic value) + :param s: current state + :return: f + """ + + return self.g_fore[s] + self.h(s, self.s_goal) + + def f_value_back(self, s): + """ + backward searching: f = g + h. (g: Cost to come, h: heuristic value) + :param s: current state + :return: f + """ + + return self.g_back[s] + self.h(s, self.s_start) + + def h(self, s, goal): + """ + Calculate heuristic value. + :param s: current node (state) + :param goal: goal node (state) + :return: heuristic value + """ + + heuristic_type = self.heuristic_type + + if heuristic_type == "manhattan": + return abs(goal[0] - s[0]) + abs(goal[1] - s[1]) + else: + return math.hypot(goal[0] - s[0], goal[1] - s[1]) + + def cost(self, s_start, s_goal): + """ + Calculate Cost for this motion + :param s_start: starting node + :param s_goal: end node + :return: Cost for this motion + :note: Cost function could be more complicate! + """ + + if self.is_collision(s_start, s_goal): + return math.inf + + return math.hypot(s_goal[0] - s_start[0], s_goal[1] - s_start[1]) + + def is_collision(self, s_start, s_end): + """ + check if the line segment (s_start, s_end) is collision. + :param s_start: start node + :param s_end: end node + :return: True: is collision / False: not collision + """ + + if s_start in self.obs or s_end in self.obs: + return True + + if s_start[0] != s_end[0] and s_start[1] != s_end[1]: + if s_end[0] - s_start[0] == s_start[1] - s_end[1]: + s1 = (min(s_start[0], s_end[0]), min(s_start[1], s_end[1])) + s2 = (max(s_start[0], s_end[0]), max(s_start[1], s_end[1])) + else: + s1 = (min(s_start[0], s_end[0]), max(s_start[1], s_end[1])) + s2 = (max(s_start[0], s_end[0]), min(s_start[1], s_end[1])) + + if s1 in self.obs or s2 in self.obs: + return True + + return False + + +def main(): + x_start = (5, 5) + x_goal = (45, 25) + + bastar = BidirectionalAStar(x_start, x_goal, "euclidean") + plot = plotting.Plotting(x_start, x_goal) + + path, visited_fore, visited_back = bastar.searching() + plot.animation_bi_astar(path, visited_fore, visited_back, "Bidirectional-A*") # animation + + +if __name__ == '__main__': + main() diff --git a/src/Search_2D/D_star.py b/src/Search_2D/D_star.py new file mode 100644 index 0000000..60b6c7e --- /dev/null +++ b/src/Search_2D/D_star.py @@ -0,0 +1,304 @@ +""" +D_star 2D +@author: huiming zhou +""" + +import os +import sys +import math +import matplotlib.pyplot as plt + +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../../Search_based_Planning/") + +from Search_2D import plotting, env + + +class DStar: + def __init__(self, s_start, s_goal): + self.s_start, self.s_goal = s_start, s_goal + + self.Env = env.Env() + self.Plot = plotting.Plotting(self.s_start, self.s_goal) + + self.u_set = self.Env.motions + self.obs = self.Env.obs + self.x = self.Env.x_range + self.y = self.Env.y_range + + self.fig = plt.figure() + + self.OPEN = set() + self.t = dict() + self.PARENT = dict() + self.h = dict() + self.k = dict() + self.path = [] + self.visited = set() + self.count = 0 + + def init(self): + for i in range(self.Env.x_range): + for j in range(self.Env.y_range): + self.t[(i, j)] = 'NEW' + self.k[(i, j)] = 0.0 + self.h[(i, j)] = float("inf") + self.PARENT[(i, j)] = None + + self.h[self.s_goal] = 0.0 + + def run(self, s_start, s_end): + self.init() + self.insert(s_end, 0) + + while True: + self.process_state() + if self.t[s_start] == 'CLOSED': + break + + self.path = self.extract_path(s_start, s_end) + self.Plot.plot_grid("Dynamic A* (D*)") + self.plot_path(self.path) + self.fig.canvas.mpl_connect('button_press_event', self.on_press) + plt.show() + + def on_press(self, event): + x, y = event.xdata, event.ydata + if x < 0 or x > self.x - 1 or y < 0 or y > self.y - 1: + print("Please choose right area!") + else: + x, y = int(x), int(y) + if (x, y) not in self.obs: + print("Add obstacle at: s =", x, ",", "y =", y) + self.obs.add((x, y)) + self.Plot.update_obs(self.obs) + + s = self.s_start + self.visited = set() + self.count += 1 + + while s != self.s_goal: + if self.is_collision(s, self.PARENT[s]): + self.modify(s) + continue + s = self.PARENT[s] + + self.path = self.extract_path(self.s_start, self.s_goal) + + plt.cla() + self.Plot.plot_grid("Dynamic A* (D*)") + self.plot_visited(self.visited) + self.plot_path(self.path) + + self.fig.canvas.draw_idle() + + def extract_path(self, s_start, s_end): + path = [s_start] + s = s_start + while True: + s = self.PARENT[s] + path.append(s) + if s == s_end: + return path + + def process_state(self): + s = self.min_state() # get node in OPEN set with min k value + self.visited.add(s) + + if s is None: + return -1 # OPEN set is empty + + k_old = self.get_k_min() # record the min k value of this iteration (min path cost) + self.delete(s) # move state s from OPEN set to CLOSED set + + # k_min < h[s] --> s: RAISE state (increased cost) + if k_old < self.h[s]: + for s_n in self.get_neighbor(s): + if self.h[s_n] <= k_old and \ + self.h[s] > self.h[s_n] + self.cost(s_n, s): + + # update h_value and choose parent + self.PARENT[s] = s_n + self.h[s] = self.h[s_n] + self.cost(s_n, s) + + # s: k_min >= h[s] -- > s: LOWER state (cost reductions) + if k_old == self.h[s]: + for s_n in self.get_neighbor(s): + if self.t[s_n] == 'NEW' or \ + (self.PARENT[s_n] == s and self.h[s_n] != self.h[s] + self.cost(s, s_n)) or \ + (self.PARENT[s_n] != s and self.h[s_n] > self.h[s] + self.cost(s, s_n)): + + # Condition: + # 1) t[s_n] == 'NEW': not visited + # 2) s_n's parent: cost reduction + # 3) s_n find a better parent + self.PARENT[s_n] = s + self.insert(s_n, self.h[s] + self.cost(s, s_n)) + else: + for s_n in self.get_neighbor(s): + if self.t[s_n] == 'NEW' or \ + (self.PARENT[s_n] == s and self.h[s_n] != self.h[s] + self.cost(s, s_n)): + + # Condition: + # 1) t[s_n] == 'NEW': not visited + # 2) s_n's parent: cost reduction + self.PARENT[s_n] = s + self.insert(s_n, self.h[s] + self.cost(s, s_n)) + else: + if self.PARENT[s_n] != s and \ + self.h[s_n] > self.h[s] + self.cost(s, s_n): + + # Condition: LOWER happened in OPEN set (s), s should be explored again + self.insert(s, self.h[s]) + else: + if self.PARENT[s_n] != s and \ + self.h[s] > self.h[s_n] + self.cost(s_n, s) and \ + self.t[s_n] == 'CLOSED' and \ + self.h[s_n] > k_old: + + # Condition: LOWER happened in CLOSED set (s_n), s_n should be explored again + self.insert(s_n, self.h[s_n]) + + return self.get_k_min() + + def min_state(self): + """ + choose the node with the minimum k value in OPEN set. + :return: state + """ + + if not self.OPEN: + return None + + return min(self.OPEN, key=lambda x: self.k[x]) + + def get_k_min(self): + """ + calc the min k value for nodes in OPEN set. + :return: k value + """ + + if not self.OPEN: + return -1 + + return min([self.k[x] for x in self.OPEN]) + + def insert(self, s, h_new): + """ + insert node into OPEN set. + :param s: node + :param h_new: new or better cost to come value + """ + + if self.t[s] == 'NEW': + self.k[s] = h_new + elif self.t[s] == 'OPEN': + self.k[s] = min(self.k[s], h_new) + elif self.t[s] == 'CLOSED': + self.k[s] = min(self.h[s], h_new) + + self.h[s] = h_new + self.t[s] = 'OPEN' + self.OPEN.add(s) + + def delete(self, s): + """ + delete: move state s from OPEN set to CLOSED set. + :param s: state should be deleted + """ + + if self.t[s] == 'OPEN': + self.t[s] = 'CLOSED' + + self.OPEN.remove(s) + + def modify(self, s): + """ + start processing from state s. + :param s: is a node whose status is RAISE or LOWER. + """ + + self.modify_cost(s) + + while True: + k_min = self.process_state() + + if k_min >= self.h[s]: + break + + def modify_cost(self, s): + # if node in CLOSED set, put it into OPEN set. + # Since cost may be changed between s - s.parent, calc cost(s, s.p) again + + if self.t[s] == 'CLOSED': + self.insert(s, self.h[self.PARENT[s]] + self.cost(s, self.PARENT[s])) + + def get_neighbor(self, s): + nei_list = set() + + for u in self.u_set: + s_next = tuple([s[i] + u[i] for i in range(2)]) + if s_next not in self.obs: + nei_list.add(s_next) + + return nei_list + + def cost(self, s_start, s_goal): + """ + Calculate Cost for this motion + :param s_start: starting node + :param s_goal: end node + :return: Cost for this motion + :note: Cost function could be more complicate! + """ + + if self.is_collision(s_start, s_goal): + return float("inf") + + return math.hypot(s_goal[0] - s_start[0], s_goal[1] - s_start[1]) + + def is_collision(self, s_start, s_end): + if s_start in self.obs or s_end in self.obs: + return True + + if s_start[0] != s_end[0] and s_start[1] != s_end[1]: + if s_end[0] - s_start[0] == s_start[1] - s_end[1]: + s1 = (min(s_start[0], s_end[0]), min(s_start[1], s_end[1])) + s2 = (max(s_start[0], s_end[0]), max(s_start[1], s_end[1])) + else: + s1 = (min(s_start[0], s_end[0]), max(s_start[1], s_end[1])) + s2 = (max(s_start[0], s_end[0]), min(s_start[1], s_end[1])) + + if s1 in self.obs or s2 in self.obs: + return True + + return False + + def plot_path(self, path): + px = [x[0] for x in path] + py = [x[1] for x in path] + plt.plot(px, py, linewidth=2) + plt.plot(self.s_start[0], self.s_start[1], "bs") + plt.plot(self.s_goal[0], self.s_goal[1], "gs") + + def plot_visited(self, visited): + color = ['gainsboro', 'lightgray', 'silver', 'darkgray', + 'bisque', 'navajowhite', 'moccasin', 'wheat', + 'powderblue', 'skyblue', 'lightskyblue', 'cornflowerblue'] + + if self.count >= len(color) - 1: + self.count = 0 + + for x in visited: + plt.plot(x[0], x[1], marker='s', color=color[self.count]) + + +def main(): + s_start = (5, 5) + s_goal = (45, 25) + dstar = DStar(s_start, s_goal) + dstar.run(s_start, s_goal) + + +if __name__ == '__main__': + main() diff --git a/src/Search_2D/D_star_Lite.py b/src/Search_2D/D_star_Lite.py new file mode 100644 index 0000000..4996be2 --- /dev/null +++ b/src/Search_2D/D_star_Lite.py @@ -0,0 +1,239 @@ +""" +D_star_Lite 2D +@author: huiming zhou +""" + +import os +import sys +import math +import matplotlib.pyplot as plt + +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../../Search_based_Planning/") + +from Search_2D import plotting, env + + +class DStar: + def __init__(self, s_start, s_goal, heuristic_type): + self.s_start, self.s_goal = s_start, s_goal + self.heuristic_type = heuristic_type + + self.Env = env.Env() # class Env + self.Plot = plotting.Plotting(s_start, s_goal) + + self.u_set = self.Env.motions # feasible input set + self.obs = self.Env.obs # position of obstacles + self.x = self.Env.x_range + self.y = self.Env.y_range + + self.g, self.rhs, self.U = {}, {}, {} + self.km = 0 + + for i in range(1, self.Env.x_range - 1): + for j in range(1, self.Env.y_range - 1): + self.rhs[(i, j)] = float("inf") + self.g[(i, j)] = float("inf") + + self.rhs[self.s_goal] = 0.0 + self.U[self.s_goal] = self.CalculateKey(self.s_goal) + self.visited = set() + self.count = 0 + self.fig = plt.figure() + + def run(self): + self.Plot.plot_grid("D* Lite") + self.ComputePath() + self.plot_path(self.extract_path()) + self.fig.canvas.mpl_connect('button_press_event', self.on_press) + plt.show() + + def on_press(self, event): + x, y = event.xdata, event.ydata + if x < 0 or x > self.x - 1 or y < 0 or y > self.y - 1: + print("Please choose right area!") + else: + x, y = int(x), int(y) + print("Change position: s =", x, ",", "y =", y) + + s_curr = self.s_start + s_last = self.s_start + i = 0 + path = [self.s_start] + + while s_curr != self.s_goal: + s_list = {} + + for s in self.get_neighbor(s_curr): + s_list[s] = self.g[s] + self.cost(s_curr, s) + s_curr = min(s_list, key=s_list.get) + path.append(s_curr) + + if i < 1: + self.km += self.h(s_last, s_curr) + s_last = s_curr + if (x, y) not in self.obs: + self.obs.add((x, y)) + plt.plot(x, y, 'sk') + self.g[(x, y)] = float("inf") + self.rhs[(x, y)] = float("inf") + else: + self.obs.remove((x, y)) + plt.plot(x, y, marker='s', color='white') + self.UpdateVertex((x, y)) + for s in self.get_neighbor((x, y)): + self.UpdateVertex(s) + i += 1 + + self.count += 1 + self.visited = set() + self.ComputePath() + + self.plot_visited(self.visited) + self.plot_path(path) + self.fig.canvas.draw_idle() + + def ComputePath(self): + while True: + s, v = self.TopKey() + if v >= self.CalculateKey(self.s_start) and \ + self.rhs[self.s_start] == self.g[self.s_start]: + break + + k_old = v + self.U.pop(s) + self.visited.add(s) + + if k_old < self.CalculateKey(s): + self.U[s] = self.CalculateKey(s) + elif self.g[s] > self.rhs[s]: + self.g[s] = self.rhs[s] + for x in self.get_neighbor(s): + self.UpdateVertex(x) + else: + self.g[s] = float("inf") + self.UpdateVertex(s) + for x in self.get_neighbor(s): + self.UpdateVertex(x) + + def UpdateVertex(self, s): + if s != self.s_goal: + self.rhs[s] = float("inf") + for x in self.get_neighbor(s): + self.rhs[s] = min(self.rhs[s], self.g[x] + self.cost(s, x)) + if s in self.U: + self.U.pop(s) + + if self.g[s] != self.rhs[s]: + self.U[s] = self.CalculateKey(s) + + def CalculateKey(self, s): + return [min(self.g[s], self.rhs[s]) + self.h(self.s_start, s) + self.km, + min(self.g[s], self.rhs[s])] + + def TopKey(self): + """ + :return: return the min key and its value. + """ + + s = min(self.U, key=self.U.get) + return s, self.U[s] + + def h(self, s_start, s_goal): + heuristic_type = self.heuristic_type # heuristic type + + if heuristic_type == "manhattan": + return abs(s_goal[0] - s_start[0]) + abs(s_goal[1] - s_start[1]) + else: + return math.hypot(s_goal[0] - s_start[0], s_goal[1] - s_start[1]) + + def cost(self, s_start, s_goal): + """ + Calculate Cost for this motion + :param s_start: starting node + :param s_goal: end node + :return: Cost for this motion + :note: Cost function could be more complicate! + """ + + if self.is_collision(s_start, s_goal): + return float("inf") + + return math.hypot(s_goal[0] - s_start[0], s_goal[1] - s_start[1]) + + def is_collision(self, s_start, s_end): + if s_start in self.obs or s_end in self.obs: + return True + + if s_start[0] != s_end[0] and s_start[1] != s_end[1]: + if s_end[0] - s_start[0] == s_start[1] - s_end[1]: + s1 = (min(s_start[0], s_end[0]), min(s_start[1], s_end[1])) + s2 = (max(s_start[0], s_end[0]), max(s_start[1], s_end[1])) + else: + s1 = (min(s_start[0], s_end[0]), max(s_start[1], s_end[1])) + s2 = (max(s_start[0], s_end[0]), min(s_start[1], s_end[1])) + + if s1 in self.obs or s2 in self.obs: + return True + + return False + + def get_neighbor(self, s): + nei_list = set() + for u in self.u_set: + s_next = tuple([s[i] + u[i] for i in range(2)]) + if s_next not in self.obs: + nei_list.add(s_next) + + return nei_list + + def extract_path(self): + """ + Extract the path based on the PARENT set. + :return: The planning path + """ + + path = [self.s_start] + s = self.s_start + + for k in range(100): + g_list = {} + for x in self.get_neighbor(s): + if not self.is_collision(s, x): + g_list[x] = self.g[x] + s = min(g_list, key=g_list.get) + path.append(s) + if s == self.s_goal: + break + + return list(path) + + def plot_path(self, path): + px = [x[0] for x in path] + py = [x[1] for x in path] + plt.plot(px, py, linewidth=2) + plt.plot(self.s_start[0], self.s_start[1], "bs") + plt.plot(self.s_goal[0], self.s_goal[1], "gs") + + def plot_visited(self, visited): + color = ['gainsboro', 'lightgray', 'silver', 'darkgray', + 'bisque', 'navajowhite', 'moccasin', 'wheat', + 'powderblue', 'skyblue', 'lightskyblue', 'cornflowerblue'] + + if self.count >= len(color) - 1: + self.count = 0 + + for x in visited: + plt.plot(x[0], x[1], marker='s', color=color[self.count]) + + +def main(): + s_start = (5, 5) + s_goal = (45, 25) + + dstar = DStar(s_start, s_goal, "euclidean") + dstar.run() + + +if __name__ == '__main__': + main() diff --git a/src/Search_2D/Dijkstra.py b/src/Search_2D/Dijkstra.py new file mode 100644 index 0000000..e5e7b68 --- /dev/null +++ b/src/Search_2D/Dijkstra.py @@ -0,0 +1,69 @@ +""" +Dijkstra 2D +@author: huiming zhou +""" + +import os +import sys +import math +import heapq + +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../../Search_based_Planning/") + +from Search_2D import plotting, env + +from Search_2D.Astar import AStar + + +class Dijkstra(AStar): + """Dijkstra set the cost as the priority + """ + def searching(self): + """ + Breadth-first Searching. + :return: path, visited order + """ + + self.PARENT[self.s_start] = self.s_start + self.g[self.s_start] = 0 + self.g[self.s_goal] = math.inf + heapq.heappush(self.OPEN, + (0, self.s_start)) + + while self.OPEN: + _, s = heapq.heappop(self.OPEN) + self.CLOSED.append(s) + + if s == self.s_goal: + break + + for s_n in self.get_neighbor(s): + new_cost = self.g[s] + self.cost(s, s_n) + + if s_n not in self.g: + self.g[s_n] = math.inf + + if new_cost < self.g[s_n]: # conditions for updating Cost + self.g[s_n] = new_cost + self.PARENT[s_n] = s + + # best first set the heuristics as the priority + heapq.heappush(self.OPEN, (new_cost, s_n)) + + return self.extract_path(self.PARENT), self.CLOSED + + +def main(): + s_start = (5, 5) + s_goal = (45, 25) + + dijkstra = Dijkstra(s_start, s_goal, 'None') + plot = plotting.Plotting(s_start, s_goal) + + path, visited = dijkstra.searching() + plot.animation(path, visited, "Dijkstra's") # animation generate + + +if __name__ == '__main__': + main() diff --git a/src/Search_2D/LPAstar.py b/src/Search_2D/LPAstar.py new file mode 100644 index 0000000..4fd70ae --- /dev/null +++ b/src/Search_2D/LPAstar.py @@ -0,0 +1,256 @@ +""" +LPA_star 2D +@author: huiming zhou +""" + +import os +import sys +import math +import matplotlib.pyplot as plt + +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../../Search_based_Planning/") + +from Search_2D import plotting, env + + +class LPAStar: + def __init__(self, s_start, s_goal, heuristic_type): + self.s_start, self.s_goal = s_start, s_goal + self.heuristic_type = heuristic_type + + self.Env = env.Env() + self.Plot = plotting.Plotting(self.s_start, self.s_goal) + + self.u_set = self.Env.motions + self.obs = self.Env.obs + self.x = self.Env.x_range + self.y = self.Env.y_range + + self.g, self.rhs, self.U = {}, {}, {} + + for i in range(self.Env.x_range): + for j in range(self.Env.y_range): + self.rhs[(i, j)] = float("inf") + self.g[(i, j)] = float("inf") + + self.rhs[self.s_start] = 0 + self.U[self.s_start] = self.CalculateKey(self.s_start) + self.visited = set() + self.count = 0 + + self.fig = plt.figure() + + def run(self): + self.Plot.plot_grid("Lifelong Planning A*") + + self.ComputeShortestPath() + self.plot_path(self.extract_path()) + self.fig.canvas.mpl_connect('button_press_event', self.on_press) + + plt.show() + + def on_press(self, event): + x, y = event.xdata, event.ydata + if x < 0 or x > self.x - 1 or y < 0 or y > self.y - 1: + print("Please choose right area!") + else: + x, y = int(x), int(y) + print("Change position: s =", x, ",", "y =", y) + + self.visited = set() + self.count += 1 + + if (x, y) not in self.obs: + self.obs.add((x, y)) + else: + self.obs.remove((x, y)) + self.UpdateVertex((x, y)) + + self.Plot.update_obs(self.obs) + + for s_n in self.get_neighbor((x, y)): + self.UpdateVertex(s_n) + + self.ComputeShortestPath() + + plt.cla() + self.Plot.plot_grid("Lifelong Planning A*") + self.plot_visited(self.visited) + self.plot_path(self.extract_path()) + self.fig.canvas.draw_idle() + + def ComputeShortestPath(self): + while True: + s, v = self.TopKey() + + if v >= self.CalculateKey(self.s_goal) and \ + self.rhs[self.s_goal] == self.g[self.s_goal]: + break + + self.U.pop(s) + self.visited.add(s) + + if self.g[s] > self.rhs[s]: + + # Condition: over-consistent (eg: deleted obstacles) + # So, rhs[s] decreased -- > rhs[s] < g[s] + self.g[s] = self.rhs[s] + else: + + # Condition: # under-consistent (eg: added obstacles) + # So, rhs[s] increased --> rhs[s] > g[s] + self.g[s] = float("inf") + self.UpdateVertex(s) + + for s_n in self.get_neighbor(s): + self.UpdateVertex(s_n) + + def UpdateVertex(self, s): + """ + update the status and the current cost to come of state s. + :param s: state s + """ + + if s != self.s_start: + + # Condition: cost of parent of s changed + # Since we do not record the children of a state, we need to enumerate its neighbors + self.rhs[s] = min(self.g[s_n] + self.cost(s_n, s) + for s_n in self.get_neighbor(s)) + + if s in self.U: + self.U.pop(s) + + if self.g[s] != self.rhs[s]: + + # Condition: current cost to come is different to that of last time + # state s should be added into OPEN set (set U) + self.U[s] = self.CalculateKey(s) + + def TopKey(self): + """ + :return: return the min key and its value. + """ + + s = min(self.U, key=self.U.get) + + return s, self.U[s] + + def CalculateKey(self, s): + + return [min(self.g[s], self.rhs[s]) + self.h(s), + min(self.g[s], self.rhs[s])] + + def get_neighbor(self, s): + """ + find neighbors of state s that not in obstacles. + :param s: state + :return: neighbors + """ + + s_list = set() + + for u in self.u_set: + s_next = tuple([s[i] + u[i] for i in range(2)]) + if s_next not in self.obs: + s_list.add(s_next) + + return s_list + + def h(self, s): + """ + Calculate heuristic. + :param s: current node (state) + :return: heuristic function value + """ + + heuristic_type = self.heuristic_type # heuristic type + goal = self.s_goal # goal node + + if heuristic_type == "manhattan": + return abs(goal[0] - s[0]) + abs(goal[1] - s[1]) + else: + return math.hypot(goal[0] - s[0], goal[1] - s[1]) + + def cost(self, s_start, s_goal): + """ + Calculate Cost for this motion + :param s_start: starting node + :param s_goal: end node + :return: Cost for this motion + :note: Cost function could be more complicate! + """ + + if self.is_collision(s_start, s_goal): + return float("inf") + + return math.hypot(s_goal[0] - s_start[0], s_goal[1] - s_start[1]) + + def is_collision(self, s_start, s_end): + if s_start in self.obs or s_end in self.obs: + return True + + if s_start[0] != s_end[0] and s_start[1] != s_end[1]: + if s_end[0] - s_start[0] == s_start[1] - s_end[1]: + s1 = (min(s_start[0], s_end[0]), min(s_start[1], s_end[1])) + s2 = (max(s_start[0], s_end[0]), max(s_start[1], s_end[1])) + else: + s1 = (min(s_start[0], s_end[0]), max(s_start[1], s_end[1])) + s2 = (max(s_start[0], s_end[0]), min(s_start[1], s_end[1])) + + if s1 in self.obs or s2 in self.obs: + return True + + return False + + def extract_path(self): + """ + Extract the path based on the PARENT set. + :return: The planning path + """ + + path = [self.s_goal] + s = self.s_goal + + for k in range(100): + g_list = {} + for x in self.get_neighbor(s): + if not self.is_collision(s, x): + g_list[x] = self.g[x] + s = min(g_list, key=g_list.get) + path.append(s) + if s == self.s_start: + break + + return list(reversed(path)) + + def plot_path(self, path): + px = [x[0] for x in path] + py = [x[1] for x in path] + plt.plot(px, py, linewidth=2) + plt.plot(self.s_start[0], self.s_start[1], "bs") + plt.plot(self.s_goal[0], self.s_goal[1], "gs") + + def plot_visited(self, visited): + color = ['gainsboro', 'lightgray', 'silver', 'darkgray', + 'bisque', 'navajowhite', 'moccasin', 'wheat', + 'powderblue', 'skyblue', 'lightskyblue', 'cornflowerblue'] + + if self.count >= len(color) - 1: + self.count = 0 + + for x in visited: + plt.plot(x[0], x[1], marker='s', color=color[self.count]) + + +def main(): + x_start = (5, 5) + x_goal = (45, 25) + + lpastar = LPAStar(x_start, x_goal, "Euclidean") + lpastar.run() + + +if __name__ == '__main__': + main() diff --git a/src/Search_2D/LRTAstar.py b/src/Search_2D/LRTAstar.py new file mode 100644 index 0000000..108903b --- /dev/null +++ b/src/Search_2D/LRTAstar.py @@ -0,0 +1,230 @@ +""" +LRTA_star 2D (Learning Real-time A*) +@author: huiming zhou +""" + +import os +import sys +import copy +import math + +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../../Search_based_Planning/") + +from Search_2D import queue, plotting, env + + +class LrtAStarN: + def __init__(self, s_start, s_goal, N, heuristic_type): + self.s_start, self.s_goal = s_start, s_goal + self.heuristic_type = heuristic_type + + self.Env = env.Env() + + self.u_set = self.Env.motions # feasible input set + self.obs = self.Env.obs # position of obstacles + + self.N = N # number of expand nodes each iteration + self.visited = [] # order of visited nodes in planning + self.path = [] # path of each iteration + self.h_table = {} # h_value table + + def init(self): + """ + initialize the h_value of all nodes in the environment. + it is a global table. + """ + + for i in range(self.Env.x_range): + for j in range(self.Env.y_range): + self.h_table[(i, j)] = self.h((i, j)) + + def searching(self): + self.init() + s_start = self.s_start # initialize start node + + while True: + OPEN, CLOSED = self.AStar(s_start, self.N) # OPEN, CLOSED sets in each iteration + + if OPEN == "FOUND": # reach the goal node + self.path.append(CLOSED) + break + + h_value = self.iteration(CLOSED) # h_value table of CLOSED nodes + + for x in h_value: + self.h_table[x] = h_value[x] + + s_start, path_k = self.extract_path_in_CLOSE(s_start, h_value) # x_init -> expected node in OPEN set + self.path.append(path_k) + + def extract_path_in_CLOSE(self, s_start, h_value): + path = [s_start] + s = s_start + + while True: + h_list = {} + + for s_n in self.get_neighbor(s): + if s_n in h_value: + h_list[s_n] = h_value[s_n] + else: + h_list[s_n] = self.h_table[s_n] + + s_key = min(h_list, key=h_list.get) # move to the smallest node with min h_value + path.append(s_key) # generate path + s = s_key # use end of this iteration as the start of next + + if s_key not in h_value: # reach the expected node in OPEN set + return s_key, path + + def iteration(self, CLOSED): + h_value = {} + + for s in CLOSED: + h_value[s] = float("inf") # initialize h_value of CLOSED nodes + + while True: + h_value_rec = copy.deepcopy(h_value) + for s in CLOSED: + h_list = [] + for s_n in self.get_neighbor(s): + if s_n not in CLOSED: + h_list.append(self.cost(s, s_n) + self.h_table[s_n]) + else: + h_list.append(self.cost(s, s_n) + h_value[s_n]) + h_value[s] = min(h_list) # update h_value of current node + + if h_value == h_value_rec: # h_value table converged + return h_value + + def AStar(self, x_start, N): + OPEN = queue.QueuePrior() # OPEN set + OPEN.put(x_start, self.h(x_start)) + CLOSED = [] # CLOSED set + g_table = {x_start: 0, self.s_goal: float("inf")} # Cost to come + PARENT = {x_start: x_start} # relations + count = 0 # counter + + while not OPEN.empty(): + count += 1 + s = OPEN.get() + CLOSED.append(s) + + if s == self.s_goal: # reach the goal node + self.visited.append(CLOSED) + return "FOUND", self.extract_path(x_start, PARENT) + + for s_n in self.get_neighbor(s): + if s_n not in CLOSED: + new_cost = g_table[s] + self.cost(s, s_n) + if s_n not in g_table: + g_table[s_n] = float("inf") + if new_cost < g_table[s_n]: # conditions for updating Cost + g_table[s_n] = new_cost + PARENT[s_n] = s + OPEN.put(s_n, g_table[s_n] + self.h_table[s_n]) + + if count == N: # expand needed CLOSED nodes + break + + self.visited.append(CLOSED) # visited nodes in each iteration + + return OPEN, CLOSED + + def get_neighbor(self, s): + """ + find neighbors of state s that not in obstacles. + :param s: state + :return: neighbors + """ + + s_list = [] + + for u in self.u_set: + s_next = tuple([s[i] + u[i] for i in range(2)]) + if s_next not in self.obs: + s_list.append(s_next) + + return s_list + + def extract_path(self, x_start, parent): + """ + Extract the path based on the relationship of nodes. + + :return: The planning path + """ + + path_back = [self.s_goal] + x_current = self.s_goal + + while True: + x_current = parent[x_current] + path_back.append(x_current) + + if x_current == x_start: + break + + return list(reversed(path_back)) + + def h(self, s): + """ + Calculate heuristic. + :param s: current node (state) + :return: heuristic function value + """ + + heuristic_type = self.heuristic_type # heuristic type + goal = self.s_goal # goal node + + if heuristic_type == "manhattan": + return abs(goal[0] - s[0]) + abs(goal[1] - s[1]) + else: + return math.hypot(goal[0] - s[0], goal[1] - s[1]) + + def cost(self, s_start, s_goal): + """ + Calculate Cost for this motion + :param s_start: starting node + :param s_goal: end node + :return: Cost for this motion + :note: Cost function could be more complicate! + """ + + if self.is_collision(s_start, s_goal): + return float("inf") + + return math.hypot(s_goal[0] - s_start[0], s_goal[1] - s_start[1]) + + def is_collision(self, s_start, s_end): + if s_start in self.obs or s_end in self.obs: + return True + + if s_start[0] != s_end[0] and s_start[1] != s_end[1]: + if s_end[0] - s_start[0] == s_start[1] - s_end[1]: + s1 = (min(s_start[0], s_end[0]), min(s_start[1], s_end[1])) + s2 = (max(s_start[0], s_end[0]), max(s_start[1], s_end[1])) + else: + s1 = (min(s_start[0], s_end[0]), max(s_start[1], s_end[1])) + s2 = (max(s_start[0], s_end[0]), min(s_start[1], s_end[1])) + + if s1 in self.obs or s2 in self.obs: + return True + + return False + + +def main(): + s_start = (10, 5) + s_goal = (45, 25) + + lrta = LrtAStarN(s_start, s_goal, 250, "euclidean") + plot = plotting.Plotting(s_start, s_goal) + + lrta.searching() + plot.animation_lrta(lrta.path, lrta.visited, + "Learning Real-time A* (LRTA*)") + + +if __name__ == '__main__': + main() diff --git a/src/Search_2D/RTAAStar.py b/src/Search_2D/RTAAStar.py new file mode 100644 index 0000000..de0a615 --- /dev/null +++ b/src/Search_2D/RTAAStar.py @@ -0,0 +1,237 @@ +""" +RTAAstar 2D (Real-time Adaptive A*) +@author: huiming zhou +""" + +import os +import sys +import copy +import math + +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../../Search_based_Planning/") + +from Search_2D import queue, plotting, env + + +class RTAAStar: + def __init__(self, s_start, s_goal, N, heuristic_type): + self.s_start, self.s_goal = s_start, s_goal + self.heuristic_type = heuristic_type + + self.Env = env.Env() + + self.u_set = self.Env.motions # feasible input set + self.obs = self.Env.obs # position of obstacles + + self.N = N # number of expand nodes each iteration + self.visited = [] # order of visited nodes in planning + self.path = [] # path of each iteration + self.h_table = {} # h_value table + + def init(self): + """ + initialize the h_value of all nodes in the environment. + it is a global table. + """ + + for i in range(self.Env.x_range): + for j in range(self.Env.y_range): + self.h_table[(i, j)] = self.h((i, j)) + + def searching(self): + self.init() + s_start = self.s_start # initialize start node + + while True: + OPEN, CLOSED, g_table, PARENT = \ + self.Astar(s_start, self.N) + + if OPEN == "FOUND": # reach the goal node + self.path.append(CLOSED) + break + + s_next, h_value = self.cal_h_value(OPEN, CLOSED, g_table, PARENT) + + for x in h_value: + self.h_table[x] = h_value[x] + + s_start, path_k = self.extract_path_in_CLOSE(s_start, s_next, h_value) + self.path.append(path_k) + + def cal_h_value(self, OPEN, CLOSED, g_table, PARENT): + v_open = {} + h_value = {} + for (_, x) in OPEN.enumerate(): + v_open[x] = g_table[PARENT[x]] + 1 + self.h_table[x] + s_open = min(v_open, key=v_open.get) + f_min = v_open[s_open] + for x in CLOSED: + h_value[x] = f_min - g_table[x] + + return s_open, h_value + + def iteration(self, CLOSED): + h_value = {} + + for s in CLOSED: + h_value[s] = float("inf") # initialize h_value of CLOSED nodes + + while True: + h_value_rec = copy.deepcopy(h_value) + for s in CLOSED: + h_list = [] + for s_n in self.get_neighbor(s): + if s_n not in CLOSED: + h_list.append(self.cost(s, s_n) + self.h_table[s_n]) + else: + h_list.append(self.cost(s, s_n) + h_value[s_n]) + h_value[s] = min(h_list) # update h_value of current node + + if h_value == h_value_rec: # h_value table converged + return h_value + + def Astar(self, x_start, N): + OPEN = queue.QueuePrior() # OPEN set + OPEN.put(x_start, self.h_table[x_start]) + CLOSED = [] # CLOSED set + g_table = {x_start: 0, self.s_goal: float("inf")} # Cost to come + PARENT = {x_start: x_start} # relations + count = 0 # counter + + while not OPEN.empty(): + count += 1 + s = OPEN.get() + CLOSED.append(s) + + if s == self.s_goal: # reach the goal node + self.visited.append(CLOSED) + return "FOUND", self.extract_path(x_start, PARENT), [], [] + + for s_n in self.get_neighbor(s): + if s_n not in CLOSED: + new_cost = g_table[s] + self.cost(s, s_n) + if s_n not in g_table: + g_table[s_n] = float("inf") + if new_cost < g_table[s_n]: # conditions for updating Cost + g_table[s_n] = new_cost + PARENT[s_n] = s + OPEN.put(s_n, g_table[s_n] + self.h_table[s_n]) + + if count == N: # expand needed CLOSED nodes + break + + self.visited.append(CLOSED) # visited nodes in each iteration + + return OPEN, CLOSED, g_table, PARENT + + def get_neighbor(self, s): + """ + find neighbors of state s that not in obstacles. + :param s: state + :return: neighbors + """ + + s_list = set() + + for u in self.u_set: + s_next = tuple([s[i] + u[i] for i in range(2)]) + if s_next not in self.obs: + s_list.add(s_next) + + return s_list + + def extract_path_in_CLOSE(self, s_end, s_start, h_value): + path = [s_start] + s = s_start + + while True: + h_list = {} + for s_n in self.get_neighbor(s): + if s_n in h_value: + h_list[s_n] = h_value[s_n] + s_key = max(h_list, key=h_list.get) # move to the smallest node with min h_value + path.append(s_key) # generate path + s = s_key # use end of this iteration as the start of next + + if s_key == s_end: # reach the expected node in OPEN set + return s_start, list(reversed(path)) + + def extract_path(self, x_start, parent): + """ + Extract the path based on the relationship of nodes. + :return: The planning path + """ + + path = [self.s_goal] + s = self.s_goal + + while True: + s = parent[s] + path.append(s) + if s == x_start: + break + + return list(reversed(path)) + + def h(self, s): + """ + Calculate heuristic. + :param s: current node (state) + :return: heuristic function value + """ + + heuristic_type = self.heuristic_type # heuristic type + goal = self.s_goal # goal node + + if heuristic_type == "manhattan": + return abs(goal[0] - s[0]) + abs(goal[1] - s[1]) + else: + return math.hypot(goal[0] - s[0], goal[1] - s[1]) + + def cost(self, s_start, s_goal): + """ + Calculate Cost for this motion + :param s_start: starting node + :param s_goal: end node + :return: Cost for this motion + :note: Cost function could be more complicate! + """ + + if self.is_collision(s_start, s_goal): + return float("inf") + + return math.hypot(s_goal[0] - s_start[0], s_goal[1] - s_start[1]) + + def is_collision(self, s_start, s_end): + if s_start in self.obs or s_end in self.obs: + return True + + if s_start[0] != s_end[0] and s_start[1] != s_end[1]: + if s_end[0] - s_start[0] == s_start[1] - s_end[1]: + s1 = (min(s_start[0], s_end[0]), min(s_start[1], s_end[1])) + s2 = (max(s_start[0], s_end[0]), max(s_start[1], s_end[1])) + else: + s1 = (min(s_start[0], s_end[0]), max(s_start[1], s_end[1])) + s2 = (max(s_start[0], s_end[0]), min(s_start[1], s_end[1])) + + if s1 in self.obs or s2 in self.obs: + return True + + return False + + +def main(): + s_start = (10, 5) + s_goal = (45, 25) + + rtaa = RTAAStar(s_start, s_goal, 240, "euclidean") + plot = plotting.Plotting(s_start, s_goal) + + rtaa.searching() + plot.animation_lrta(rtaa.path, rtaa.visited, + "Real-time Adaptive A* (RTAA*)") + + +if __name__ == '__main__': + main() diff --git a/src/Search_2D/__pycache__/Astar.cpython-38.pyc b/src/Search_2D/__pycache__/Astar.cpython-38.pyc new file mode 100644 index 0000000000000000000000000000000000000000..7d90ba3c44538ba88a6880eb06eb10a78fa65dcf GIT binary patch literal 5495 zcma)A&5s*r8Gqk*#^dp<*V&|LvVpct=n~=(c46T0-SoOH;Yt(tXjd92-6d zttx8zwHcprPrJxwoYQ=LU=7z=Yr}f0&e=Q6t9ZtT%rlNeYu&4Q=7+4+@XvU)10kRK zjU$FR;sI+~lgri}Cr(^x-`KNmyW^x6$z8iQ4u(P4wI{u3Y(2*z+5Y6!o$YPtTJ|Ru}q5|#hL!z{d@bFarcMs zJ-D}*>0Z#rQuput=-&RrjCY%QrpNxEBP&=%8bk<%A2WFl*}sN6y=ds~5Wjcc36gim zk9O|6Nv~w@iy2KzOjJ@$To3LIbuaS3Z2H!w<@ ziHmHi6F&OlpejEpPodppX?`B<5<6fro!8J#s{>Ojr_^vpEkEI5dbo!j&d@k@^0f}h zv6#H8fJ@*l@y#^kkKu?~V>Lld{n`?#Vihs&<^m?qKX^Rn;DiW0* z!i)y5^9Hc9@wu)Ue1q44Cm|aA0`fX?po_mECTDVFl`FJKz~?`b4uY40);Y%@zbApYw8+u>B$>+q$E)sr!e-j$uoGf;O)*vO0r(4no zU&gSeQM|vO>BNt$T7V?eM$SP?d+Z#nvSG7a%PE(4Nzm2vHE8pyB}{%ny}czSudTfO z%Cr-@mq1lRQfvJa1!6!d5?HSz9^lcTi+RAOl`fkaNY#WNi`0NbaY!O$4{U&(oM#s? zvygE^eu`0gYAE?Or?s?tTuEV1A>Fl9K(>2_pJJv#ZIJEW)WUi-CD~Psu#{x4rD%m* z|28rEHS}AM-ZjdVOv}8Cwpv=DzVck?FV1BZ=dudPmWOX)SBqeiRtuo~sbsnwhrodS zBuIL5RQRV5Q<#ulo8F&HF%^;p+IDkb7B97t&qc>x@2u4R?Z zAaWCV5j6>a2%=k>Hu)uLBuM#2qw$K{#Yp6a%im!pN+6Humjz5EMLSyLA9fVcV80V2&qKa729%CUnvQg7d>w=wl=ru${8!9l04e;lOAs5> zNR)61s&&L~#Gy_GCui^$=BdYp|0lM;mGSY%JZFG9S4OzB!26?jXK}!hBMbOLC__7C8)TlyiRWP>Hrs(0PhNtkigQa_;oXZDPy( zM`gOZQY+s@LFscSmYI;}65fYNg}`bl{L}f}H({JTGVjpmm)Itok=fNIe=8sNt~+Rt z2aq=VF8P?9NP>ewZ0EjOIc(0h+}T@_)G+eCP*7nzfrRD$Ig|g#W`GYwIX}=iY?Idr z7kE7I>_Zm2OSl>41&-{h|?YVVPan`tiW|Ub^x5F z4G@+LJgq-Y0C5Fnb8~@ZcI__);X^qF%9gjWckH(z#%Lu4R_YowU01vAfcU2JiiZ$V>k@h!25`dk?-!}yfW zCY_{|0mUNp^2&c;$KcY8UsN&Lvd*@DV0S5s+_tZF3-L-K5+(n--9z|1k1lQH3^&Vb z&xL>2ZjYrTX06!gxmb6~DbTda(vgOiZxC4#uuEwBJ?m3IN~R6O1C7{x1{#^ zteZzTjGWsPh(s=MZ^Rt%hw|t}$j0IJVIx70vR{1i)AD@xa_>Elq2V#w>cfByJwxGk z9)D8wy#&1ZB_CqIsQ7@OLXvXPrk;nW$}b>|km+O&&`i-mZuP%TC7Z~~gOJbg2c%f} zo`%T{jV!sfgoWjh6vN!qFGVUtR zwcl*e$AHis`i_%Xjx&tB@qo&8$2lCkgQBPEI9}9t97*yiUnfHToATzC97j?Ik_19I zj#A0Y0v)QP`~?yOLXuJ&Z~%pQ#4sCayeIAqEb zpoBPoq)lN(5PzUHqhJx?;EWZaAz?vJE1o{n@a>H>N@c$(p3{QzO%Rm7iR?L@zE$(b z?LpxAZa5Klu7MqN7)j1eX5KHpvZ+_dYHk=HGKXnK=%yB29fVf4WY)r9&ULl7Ze^Bn?b3@zE L8XvH?z%~9KyL;g` literal 0 HcmV?d00001 diff --git a/src/Search_2D/__pycache__/env.cpython-37.pyc b/src/Search_2D/__pycache__/env.cpython-37.pyc new file mode 100644 index 0000000000000000000000000000000000000000..945aa4dd30ff0b41097d4b473bf4321682bfd244 GIT binary patch literal 1434 zcmah}&2G~`5Z+xovFrX&Ri)|y6$@2@94Jt3QH3fR)N&xIRG~^y(Bfv@#wD@SU8hQ; zL_(wwz$3I5BwmCocOT(GUV#hDtR449NNl?^s8KyAa^f~lT@5OhE| z90(*FNa)SN61JEU&XEnP;JGj^30S5e061M8KZkwe`yfhe{0GJuOt2-~pNugB*ac9s znA)gr*yw~9y^fnE@tKWEgOv)2)#K6&kNm_sn;7jV4x&&cR&=0v+v_9-7$usR%5NQh zC2|(F|NgX9uD?~jRP~*#nl-3qz2d76anz}A2XV7|@VK_~roQXN&E1w4hEVeQp6|&< zlOK4>7yS0>dgaO58vg$$s_uuUYn`*i<~#_4m~*VS(mbI>__OI8?ax44)+PZBY%C7c zICXz;#~|$wR-RT%R8GShlxqf*w)JgOF$Zgj)9nZ^_BoW~4ty&OO#5?~?aGz&0XuZ=APMay^i0zvp}{StNX)SSQz0BFA~B0>jxGQ>mvTL?zZY1l7g>KAiIhFO zYN?1E552a}dE#*1jzqVG_6+AIU9XjTB;G;d$#u?a=fIaLk+u?lHSj(P$!JsCvJJgf cEwRMnTtp4d^}@e)C-z2~`33%RXv&+$U$g)@-2eap literal 0 HcmV?d00001 diff --git a/src/Search_2D/__pycache__/env.cpython-38.pyc b/src/Search_2D/__pycache__/env.cpython-38.pyc new file mode 100644 index 0000000000000000000000000000000000000000..e45c75b8d0504fc65225c15ff892fb552c211b30 GIT binary patch literal 1405 zcmah}&2G~`5Z+z?#!X9Am8#-Ud_V$U8dM|>6+)FLDqNyU6&xa=m78@Nm&8ujcGX7C zDSZSUpgnTqz;o~bd*x&vflHaO6E{Ifth2MT`^}F%^KCvXFFOPVZG7iVosgfnnI9T# z_FyI(AOz`<10twk*F>-h>rkN`5ln_u%8XoZJ2LhCeJ|#niCE$ z1`=LOlmUb#Y|#+TsST%q+-SE1G+ht~y3{USfM4+#gvW|I7zL=HOQ;1YFaziYEYhrW zTo!Z$!KOS%rBIz8^(U0wnrtN zL5-GRDfRLbE3ph`%E^YpPXi8hcmVsP3{FQYnDHK3AOf}k>tE(%(6pSKkul^wqhpq` z2^njtmeUE{C!f~Fdam8*xi07lyQP$zKdP~f8J07_Hpvu!2{@bg1)Awo>|>41eBo|v zk{Xw3$>s@L$ZSl#zW{11L^f;BZ-@zN-cwjL`U6mV!Lw0gzjC~j&gjT-r{g{JGxYo6 zC~%>wso(7f$y0Y2CvXhptL=7WkY+O4b%BU(d~$DGTijoT0{d7zM1gH8)=_MsSVi#+ zgl9+#7KubsS`wtnsOYcxLI8*qQ1nvKtC9$chJSHEHoyWIm|!?!A`MN}q^q<^*Xwnq z+^@3PI$A=iOz%_MGm+7eKL|Ki4(EedWPQ||oS$cYze3~+#FzLXWzMy&t;Q7J37-C?se`I2;Tl zJt0E-fuBYX`pU_V|&X1cH|dhx6#}-t&4L|Npbs951&RFGfSF)9Vj}rWR-@~*MmH3i#-?4flp8(F(v*S;P)g*HJjR&trfAB$CSmn Xh`XE@fxEJm{c5)JYb;ZcS~vd!GNH!Ld#tF63G1rDsHt!(9>b&6#*T~$(L+n91M8k>)*)X|7g;`~o`9N9n=)yc zW0h@M5na?$c?Tu?GOCdnNokF&fQrcFp?yS>99i4)&|%qC7TzY-8=jGS@1oq)5>FcY z+r8apDQ#szH|!f5Lc=yr7A2e7!MJu&ePZbfnoq-b-q`qI7U^u`*2Kb1Sa{=llsZQgos<93*DO^v&8qRFSdm#=U1C;F}R_f0tn;$EBw!D)Oj^H5o$E_^XO zJ+;ExbVi%jPZzaR*c=2-m;Gh27}5I+d^&cf&kRd*`vPjMTPZLi!u7%ygPf znyEx)B8#&f??ZT4r6X(XbgZ$v_oH0q_DI~r-*xN58)FaioRJ)P=dF=L^^t_a?xCkx zb&Qta5$Y%7xP|;0-ZYVX>yxPLoszNu1@uW#j6w*NKdsL_J-{uwJG)Za*9Vz^AB#JZL-}b<^EQ6Wki5 z0wQ2FOFu@{Dov5?q*)`g2ko@mihGd}JI764pII|VbRIs9=duf^$nIs~$Q7{)sV-^^ z<{Ek8>}Nf}&z|g#1n)ZTjtx0>;Er1lx#RVd-GOH(hKB>-3b@9GlR&_VkxCB0U3q3; zd;JF;QoyqQdbLq0EbPxMtj}UZpQDPc%N8XQYr@>;nbT<}!LFgYub-f~L@f)Oab<4G zP=`U5hx#SV$mla<&Keu@jHt`u#S=_8eWp#sMHjW?YDV>o5ZH{)1Y6js*tEbadLOk_ z3*}EOZqlF?7a(Gl89eSBJjUA%Hd7r@+X~w|jHA!dvlRy+>G=j$H`}fZl9M!?&Ytlf zX-8VJhC>JxWe;dSS=SL%#uCA5@!rk_bhWk-!mwkhbpZ&E0a1)NlM#eBjFe_0u$3xL z?f@s=l>+;`LK0J(zup#D0bRtRw6yn8GTKQUeC)&8Sd0)!&s)EecN~gHn&z`{8q&zM zuNkp-%v7KHZ_=j5?(1K9i(W==_N?J^GxxJ=h)UPqOwx9kWLF?eANgMw^k88@`Z-$M z^V1d1VX7(YzKt?jOrb>s9Y(e?BReSBj&Y+qgD?TH5VsZ-fkCtz_3{}? z$om8^hAj~sS%bg1l4D=p6FsS{jsSG+b>l@@JM2gNHGIX!YmF1_#W@m6m*0ELai;uc z5_VfEyz&8F{Vx=2`252-p2YS=C>KvWurd1q?W6~^zz0uJML6vI`;&kE<-OMJtDT>$ z{^91|h6h(0et|HGL7c)d_VgNVjooQ)8m}GpcEik6yZr=lt=Eg%c|qsI-wm%IGY*0m z=^@x}(93xz7!NVElW!fCyr9e+$*{g%imHiQ3|hm=GyFegbLMj*}+mx0LA`yBqG!IaI$zpQZ4x z2^kNe^Gno06xb|-Cpix+B+dj+$awV^F*!%ch|uT6xgu9VoX=2^M4n8U=N_eHo1UeM zLc=T@q;*g>Sb(VGj*;ilPZb0R+#%AB#3uckQbjDw;shrlru5swnDD=i3@5S<#&m2px#@C9013kW~H!3Lm^JDMj(; zORey|~%WCR%%rTWLkD@}Il8U>m%y((PSE=eu zQ2c%BK)N>Qnp53K#e*(u&PJ#e9sPmsBYE?wZ#PbpC@(Y?n)vCsvh?G^Z%~dYJ5?IW z%7vIXS2no3jx9j@54(cc^+scvekq~De-Icy2)d~nBqY~@fHKZvL{~9a*Qk1&swb)X z0#(maMW^P4(;LCi)Nl^T<90W~FKJ4XcQmbfL6iCZvoS!7%Au_+%5K>%d*$VF6}9g_ z;n&M&YIRMs8g)|&0+qJ0LYZd9&h|5N8oyBx<0f$nzxrO8*bSKsPr1dXR?7zaIzf zHb$=1L~e%dod%7aK1|%)!kO+uga!;T3M2Ln&s3(eaJ7o5dA2I4GVUE!Q7*0}HKVGy zmes79!?mKWsCjjEUwE#1UM;F~&}P(zTwj;GI?Mgk|z7cmOQXnx0Uh0I1=kMCzreL;Jm9P zp7hMO+dEzuh2n=z-krc2tmsK0LC7`;=cVde4o2c+%gXSB?(S z$H93OH+|#4=$nLWXb99$lYL-b7@0`{0_w+8v-1kMz;EhE#(Q@L4n|ph*>^4)eT(Fwgwghaqu6}(mJl0iCkNSu z{&jlKc+A7Az;U^6Z#(+uefyw7cS9$Z`Zhb!K5$1)tjYD}?|w_ipKjJ>^eiTtR~t#3 zXg`k9%)ge~I%qe;+>FDvoSCbXu~E>eryK8?7O}uw1cpfmpOYeZdwkI5WLe{d!bDi4A86 z*%Jum&W^v4=#Z}Ups~$pdWN<2$PdWcw=lo)q9wSTYUgP5F-9aC$yT$JqN z7CSe-MK7bbI!FY)m&b76AQ82$UXPPT5T`ewj2`+d(|R(VmVRY4!3kzHWq@x_&!sSf zke17On#*SD$#mPZ!-w4<2G0=97K~)kTqjvLx3egVL(d9!qjX663>?p<^u1eL_D=YO zv3ZLoP^^-9F)x?Ja*;(Rls|S$ZZ&nVcdXnX(x+K5bp8y5K+_kXuJJGc&iWzNG}E1SKH}eAb5+XG8nYp!$%CD^=R(bkR4n zGNlw%zGQ40`h8Uy*zM=Xt?r^R>^V>~=&@9FVE4_wy#$bNOZ^6NY(>q|93K|?+!%^y z)~DhjlA6qIX0qIA1$sNw`PuDo&(~obqHy%Xov@u90|^D6@XOdG&LeN|uP$U*V2?#x zDx)cYUvoWo!n6@|LjFZy*u<-IE8LB;BZ2tSyH5l!FJF&?R$T=*evDWD8>i8G3$l`#S>3VjDAAP=?P8n$@3(rSp4YYqksM7-TM8TAN_3c4|o68+rL?J3zSh>;)0Ly z$K0Bm&BjLVG=la{kmfV3PK;F7ZikJmV0fbRno}?v=fz8CARl&NObxo{Ak8+j%@dY! zYWN=d)0ZI%@+JbeWEoj;8F|q8#4_iFgY4)?%cAVqJ9nz-xzKlxWk$j)o#cS@0OA+M z2Jb}n%bAgh4?uTRoPhK!?jhnk*#rEf_cFOXy_QIqMsC5{#D7O)HOO==? zEmZ~`R+s>b9&8Y}$L1b)*yE^~F$$}v6Cyb@B~URT&JQs4J{HY{6g4@IJ$ocI#Woia zh?1)m&Ydpx69rMiekvVO1v3qxXVT&SpVSxWNBQR|!1~_!c03y@SH`o+#q0VVG+^yj zV$@KNA_cg-PERql5>@Iikys^h8v-;rDKa?2QXMd%O0G0Uuw-u#EIn%@4w|0B1>5fM zI^;{9B+rk^l?|LJz1IK~m!%~Zt3fW3K!MlxJ|IWUiFVpv;v; z;S34hkl@LIm01}vne`Yg;Ls1iYq$po_A_UT3TH~a#G{1i^SF_w9j#ugRcR^`A|?Tt8j6zY214fR*i_}MsBe~sS!CW&v5V9ZT$e;sZ6)c#F~-m9mQ z2kNwG`vHHzfI5FA#s<)G&_Et8eW9(%3wq;{|b!@ zz*EXyeHDW2sS95C#`X-}kANSufu<*Z-gEH+G1is9eKmOZUcZOSLxkYi>O zkx)=6rYZS)V)m5D?f}b`&DB4^7}%19VPRHDMJ+b!`_$p8L^X%-eLxK;)w(V3Oe<7T zx5XY{XH<)ZPFHtOxVhA}6D4t2Xm+Cool z3dA>XY>AIKQx$=?}?yMA= zM%L!?lJBdefmzBV&CPT#_0Hm>1rcr>)$v(~G|)F+i^WGApF2UP6Sh^3SZOjWF9r3K s7@B;r5wYEs@pmTv{Kda`+N4o=6~4Mb(BWKQ*;JZTam=duKZnt<8 literal 0 HcmV?d00001 diff --git a/src/Search_2D/__pycache__/plotting.cpython-39.pyc b/src/Search_2D/__pycache__/plotting.cpython-39.pyc new file mode 100644 index 0000000000000000000000000000000000000000..c381ea6565fe0c10189368e3029be1494803ece1 GIT binary patch literal 5332 zcmbVQ+ix6K8J~0Jva{p0P$ZsbgrYMKSiYs-%vuyMEHVR=}T_Sw&mNxh~$Q|Ux@^2 zm+NZe9f$*=%#+4}5VY4y=GryCCXCyLvX!%EDCeQ{=asx`)GPfLygNxZyO4FeNqXVZ z4exrmm92O6lJ2023|wMy1}TUC^czN4zjLt9aEs)p88^J)QY zRh?Ih>iC}UJ@t%QR!@VPQzz6(%+;cKbxNJyGad?m0rVMlmg!^a97KJ#a7oe(oHmK0 z(L*$q@1mq%MU{(ON+UM{Dk78n<^fSMH#X$H#k8%AyT&82T6YS$^L>=tT4HBm-t27q zm2M*q+F`FSLDbE{N~2^=+nCo5sz-(<`~N4udHLR*Fk2s~@6~pgW|2N}>_~mz8;)MO z@g%EER^96j#b4>|7H$y4oj3~uc%YFIUxru^p6DMRDQRW2qDi8S9-^tRwnz?W3z{N* zXbauC&@MGnSJ5!d;+EAM#tLt%r@|}>pq&%wr~G=+e`@^0lldmSa`X^AHq^`LRONaH0ou6lO2UV6*k^gSy2+ z6c&$HMr*B3*p6m}s)n7o9cFR2a~hnbqyq!$q`&^sShDe=LxRzPCkwDne+A;OUvV3n22+&OLJ7S#t5LfiX}V(~Fsfo*7<6l9n5TlAjsn)?^w z({65W8~W$DyGe?W+mGD-bjgcx!U^eZ|M2cwfdZ10HZ~%*-g4SNa8dLE)}*8 zJFTcNlc=MQVOo=O6?QM&N+Z2U19S=sM@Q}McBGfksaHxzd5UJ2sd}20$Y$c#NbNzh z+it|2s1Td8Dqk3DGe~q6K8teW)i-bBOt6lOH} zSE*grD5+SJ*iTZY)l7ozg6f_=PiyJqP94dmi7G=K25A=R*RUcb82j%sYCBrX$N<{R#+Hqc!v|99JA&cq~T0_`sGbI5vG$gGOAs5(~~QWKUeEaJGZB zu8yc}gw0L%rYA_-hy$Q*s4s)R@u4MmIa1Ei>O+V~GLoz;XCDNG=RL@^Vcb9@8c0OA z>Asl>NNj8%?&0K8Yr`=dc8qey8qOdlVx}^lfyR_O?7^-0dSk6|#{QvX%NW z-Sq9~{#KX(UkHm!B(jLlNhB`pEY6b1x5Aw`9fCbOjBis2-zl5j*&nAvaUErNIu^yE zJR{DO(Q^XzW0e$EONYCMQVs%p0)2LwKZ77=$pv8eL@p4?&?}G0295?sUm1=vW+*X0 z7(fX4aA3h9Bp}_)%nd8Il%Ptl$k#-^b^ zRMmmqd1gH7EgQp`eKm&}OVtK;Zszt0IQOR1Zz8r<)jaWdzoZw&E_iHp${wOymxav; zRygfYZ$`Q}z8UQXI!YoWk3qB@b+SVaLWU>5WuGO$BW>`nE@e1a4@E~Rqb1A!T?jfY`=+LOy2k4nM({qLiH{pG#Jook=|Z26D3|JL8TR`*ITJBwLP`q=;U*U>G^R&%Xz znqg-kd&r!S%^ zL7RZvk}jg*8N@&5Gs|2Q4x*wXEsLUJ|LG$|FND5zC?b--QXvJT`>1|ltnqDR&&`ZX zd<2-Iqy%7R@eBdp>VoLMaM!QiwM+c>vB_H9^kwAXadb zZ_qTuDM2L1b^SU~H)&~QDyiUzN1Qlsb%ymX+}~G;0sgesaGMjeuJtvQPoZTL!#N9-vm`G zG`qU9mUJIPx{+)}`YjB8IV{z0)0-&?(%+)W8&_<}tLX005QW?R%SVC+^0H~KA3`R- z=mu?NZ>!D1A}6zSAPch{?o3cp-=aOYsrnvO)2R474ZMKLcY%bQ?v)fLd`G0W`Z+Al zP|^#iCeXMfmjI2=Q;{V+GAN$Sj^SB zT{vl+;L79M57whF^J_`mTF=tWT{2uz)!p4NA=0m=3GT*}G1P6gz3+7SR)wz|QPdmm z@J)?Nt7x;KaM!*7M)X&xnz0;RihhYw-teVsyY|#YdvdinB-$thvuHK!hDa=0PC2Gr zMRa=~qu@1*qLS^3ird7r{t-=hs;gQ*rvw6d+?AIu%h02ib+*A~s2ozje#eO{&Xe;s0GQkI_z+4LPT1>39aX?CnglBU5-NXmyyUXq! zQX;>>2f>g1O8eR;zCxcmvuDSb#J2cT*4n>wp5N^3Z)SdPw_60-uzrodb_w|hH`C_8 z;vRH;7Y0EDjY&|>G@uWNV8VG%g!7IC40bi)!p?=A1G~Ctz^(zinxM}}$NLC6NVkvU zv@uxRgRXytL6U$95->pnr_>Dpv^oQ~)E3l*Cz|g`&=4)qxMG@53t7mWKX#rRy=?i= zw&PIiE&uq~9^RL_uc9oE(xf8tBkc>Rqy0n*e=k-3PNa0c5hWYtA}w-X6|vm3I{FkW z#D+7Py$xNj!H|;=bWBEsGeN*8+U+=IrJu&J>?5K!u8;?XG%gH<>`+tFGT!@}s0RG` z-!zkJJgF#yKz~nc1n)Mz;`Ji~U5j=d{+YR%p;n+W$Q}MFM+?0m4gRcGmBPnT=sAVXsN4=YqtLqw zU53urXt!6ZG0(xDJ^uzV_6TF_#hDnx;{`E>qBAk}DEyy7Od(xV4Tr@Pw9dSOPC7w+ zwCpR0uh8SmQ1SJCuAr8*x2RuCd$kG*C!AMpG{90}#s_4})e2}yc?#X`7bK47(~y z)zM#P=xxsz@Y~9KB~u0YNBc6CLz(2-FEnQHw_#jJ|IZ8+NBLnHIg1m|J{FMUOh=co z3lqd|=%NXy*Jn5Q)}+2sfjwV=Em@5bi4A9r$!+NRG7MNDA+xd(8__*BX0w#;7LHKiZ<^ zC?ub0SZmU3*)yP?E$H*WArMYHHR`tDSSGQ?lm%_sGn=MNilJ0tF7H%OE>^C1{6V+V z{N$kf36xd*ILja3gWwt>VWOGU6R0RC>9}RWMfcbeqc9?^Xr4CX-7f3gUA(%+g5^=q JSzBLQ{|}hB_<#Ta literal 0 HcmV?d00001 diff --git a/src/Search_2D/__pycache__/queue.cpython-38.pyc b/src/Search_2D/__pycache__/queue.cpython-38.pyc new file mode 100644 index 0000000000000000000000000000000000000000..69c46c686152f84441b374e99fc01ccabf6439d4 GIT binary patch literal 2668 zcmcIlQIFe15Z<-pi<7$?rB?w31g-=^5i|jW1gfAq>8dM8RXB9w#T6{Bckklj*uGsG z=}viTe+YTZJHKXMdFo%_iJ5gAn>&Y!12)<5?vB0R&g?fc-wy_T0*&^5V;?z${Em}m zvthCiUEK%438yjf%O~~eL&7a?KPTLNX89J(I^2Po12Y?DTf7UiF3dWd9+RQ_0`?%2 z5M{GjFxiK$J_aF(PdV`|PJO%F9lkdE`cAo{zr|hNdrtf=@58R!y7yfn3UT<&;kOq* z_C06^aiG*aZ@p|59|#r7D9fWXX{fwNd0eRIG!fi8Nu_rfNtNG?lDp*~Epks5u^5>> zLJB9W8jkVk2hi0nh@AXN7i3PD#mO;Q(#g`++hH2VB1BZB9WKrap&bx~SW?|lB0gCX ziC6H)Y&=b8Vtg@8i}AxK|GIcGJ__>bQ5+;ml$?%_MIgf|dlD$Y+2z$wAB;yM{J-oi z13k*lwaZwPL^)&Iczm>j(2JXEmyIg*%S@h=r}P=+^k)l9wk8t2vb3}vi$r!|EL{|6 zVJQ$!J7SjQ=jgKv`IQ>k=t6TMcmW%Zk%-3AH(&su;OjYEPzq!`CK9zv%K+-FAj?F; zVcLULzmud~Tt0xE75S^6t>6bWJZLuCjCPdZiwbtQg6(E$7K@X-)nNNnmo zcpphH6O8FTW3!Y4=U}|U*jW+8D@~U%o`#Ic9oR~uBP4DrUqey5*o@H65*-IoO%yJ< zwBxuo{>*v^OMhwj@;>x`7lw~841c&1hPb>T3{iC@3?BvmO%xht$PSp*b}z<}@1V_S z{5k;eMAr%cIY1!fbt@X)*d6E6H23SdP19n}C+d%PF z!;pXIC10dg1aNs22m>H^F`+qf}n} zbcLyAeFIgE&XXdQkW!Q0 else 0 + heapq.heappush(self.OPEN, (prior, s_n)) + + return self.extract_path(self.PARENT), self.CLOSED + + +def main(): + s_start = (5, 5) + s_goal = (45, 25) + + bfs = BFS(s_start, s_goal, 'None') + plot = plotting.Plotting(s_start, s_goal) + + path, visited = bfs.searching() + plot.animation(path, visited, "Breadth-first Searching (BFS)") + + +if __name__ == '__main__': + main() diff --git a/src/Search_2D/dfs.py b/src/Search_2D/dfs.py new file mode 100644 index 0000000..3b30b03 --- /dev/null +++ b/src/Search_2D/dfs.py @@ -0,0 +1,65 @@ + +import os +import sys +import math +import heapq + +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../../Search_based_Planning/") + +from Search_2D import plotting, env +from Search_2D.Astar import AStar + +class DFS(AStar): + """DFS add the new visited node in the front of the openset + """ + def searching(self): + """ + Breadth-first Searching. + :return: path, visited order + """ + + self.PARENT[self.s_start] = self.s_start + self.g[self.s_start] = 0 + self.g[self.s_goal] = math.inf + heapq.heappush(self.OPEN, + (0, self.s_start)) + + while self.OPEN: + _, s = heapq.heappop(self.OPEN) + self.CLOSED.append(s) + + if s == self.s_goal: + break + + for s_n in self.get_neighbor(s): + new_cost = self.g[s] + self.cost(s, s_n) + + if s_n not in self.g: + self.g[s_n] = math.inf + + if new_cost < self.g[s_n]: # conditions for updating Cost + self.g[s_n] = new_cost + self.PARENT[s_n] = s + + # dfs, add new node to the front of the openset + prior = self.OPEN[0][0]-1 if len(self.OPEN)>0 else 0 + heapq.heappush(self.OPEN, (prior, s_n)) + + return self.extract_path(self.PARENT), self.CLOSED + + +def main(): + s_start = (5, 5) + s_goal = (45, 25) + + dfs = DFS(s_start, s_goal, 'None') + plot = plotting.Plotting(s_start, s_goal) + + path, visited = dfs.searching() + visited = list(dict.fromkeys(visited)) + plot.animation(path, visited, "Depth-first Searching (DFS)") # animation + + +if __name__ == '__main__': + main() diff --git a/src/Search_2D/env.py b/src/Search_2D/env.py new file mode 100644 index 0000000..9523c98 --- /dev/null +++ b/src/Search_2D/env.py @@ -0,0 +1,52 @@ +""" +Env 2D +@author: huiming zhou +""" + + +class Env: + def __init__(self): + self.x_range = 51 # size of background + self.y_range = 31 + self.motions = [(-1, 0), (-1, 1), (0, 1), (1, 1), + (1, 0), (1, -1), (0, -1), (-1, -1)] + self.obs = self.obs_map() + + def update_obs(self, obs): + self.obs = obs + + def obs_map(self): + """ + Initialize obstacles' positions + :return: map of obstacles + """ + + x = self.x_range #51 + y = self.y_range #31 + obs = set() + #画上下边框 + for i in range(x): + obs.add((i, 0)) + for i in range(x): + obs.add((i, y - 1)) + #画左右边框 + for i in range(y): + obs.add((0, i)) + for i in range(y): + obs.add((x - 1, i)) + + for i in range(2, 21): + obs.add((i, 15)) + for i in range(15): + obs.add((20, i)) + + for i in range(15, 30): + obs.add((30, i)) + for i in range(16): + obs.add((40, i)) + + return obs + +# if __name__ == '__main__': +# a = Env() +# print(a.obs) \ No newline at end of file diff --git a/src/Search_2D/plotting.py b/src/Search_2D/plotting.py new file mode 100644 index 0000000..1cf98a3 --- /dev/null +++ b/src/Search_2D/plotting.py @@ -0,0 +1,165 @@ +""" +Plot tools 2D +@author: huiming zhou +""" + +import os +import sys +import matplotlib.pyplot as plt + +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../../Search_based_Planning/") + +from Search_2D import env + + +class Plotting: + def __init__(self, xI, xG): + self.xI, self.xG = xI, xG + self.env = env.Env() + self.obs = self.env.obs_map() + + def update_obs(self, obs): + self.obs = obs + + def animation(self, path, visited, name): + self.plot_grid(name) + self.plot_visited(visited) + self.plot_path(path) + plt.show() + + def animation_lrta(self, path, visited, name): + self.plot_grid(name) + cl = self.color_list_2() + path_combine = [] + + for k in range(len(path)): + self.plot_visited(visited[k], cl[k]) + plt.pause(0.2) + self.plot_path(path[k]) + path_combine += path[k] + plt.pause(0.2) + if self.xI in path_combine: + path_combine.remove(self.xI) + self.plot_path(path_combine) + plt.show() + + def animation_ara_star(self, path, visited, name): + self.plot_grid(name) + cl_v, cl_p = self.color_list() + + for k in range(len(path)): + self.plot_visited(visited[k], cl_v[k]) + self.plot_path(path[k], cl_p[k], True) + plt.pause(0.5) + + plt.show() + + def animation_bi_astar(self, path, v_fore, v_back, name): + self.plot_grid(name) + self.plot_visited_bi(v_fore, v_back) + self.plot_path(path) + plt.show() + + def plot_grid(self, name): + obs_x = [x[0] for x in self.obs] + obs_y = [x[1] for x in self.obs] + + plt.plot(self.xI[0], self.xI[1], "bs") + plt.plot(self.xG[0], self.xG[1], "gs") + plt.plot(obs_x, obs_y, "sk") + plt.title(name) + plt.axis("equal") + + def plot_visited(self, visited, cl='gray'): + if self.xI in visited: + visited.remove(self.xI) + + if self.xG in visited: + visited.remove(self.xG) + + count = 0 + + for x in visited: + count += 1 + plt.plot(x[0], x[1], color=cl, marker='o') + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) + + if count < len(visited) / 3: + length = 20 + elif count < len(visited) * 2 / 3: + length = 30 + else: + length = 40 + # + # length = 15 + + if count % length == 0: + plt.pause(0.001) + plt.pause(0.01) + + def plot_path(self, path, cl='r', flag=False): + path_x = [path[i][0] for i in range(len(path))] + path_y = [path[i][1] for i in range(len(path))] + + if not flag: + plt.plot(path_x, path_y, linewidth='3', color='r') + else: + plt.plot(path_x, path_y, linewidth='3', color=cl) + + plt.plot(self.xI[0], self.xI[1], "bs") + plt.plot(self.xG[0], self.xG[1], "gs") + + plt.pause(0.01) + + def plot_visited_bi(self, v_fore, v_back): + if self.xI in v_fore: + v_fore.remove(self.xI) + + if self.xG in v_back: + v_back.remove(self.xG) + + len_fore, len_back = len(v_fore), len(v_back) + + for k in range(max(len_fore, len_back)): + if k < len_fore: + plt.plot(v_fore[k][0], v_fore[k][1], linewidth='3', color='gray', marker='o') + if k < len_back: + plt.plot(v_back[k][0], v_back[k][1], linewidth='3', color='cornflowerblue', marker='o') + + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) + + if k % 10 == 0: + plt.pause(0.001) + plt.pause(0.01) + + @staticmethod + def color_list(): + cl_v = ['silver', + 'wheat', + 'lightskyblue', + 'royalblue', + 'slategray'] + cl_p = ['gray', + 'orange', + 'deepskyblue', + 'red', + 'm'] + return cl_v, cl_p + + @staticmethod + def color_list_2(): + cl = ['silver', + 'steelblue', + 'dimgray', + 'cornflowerblue', + 'dodgerblue', + 'royalblue', + 'plum', + 'mediumslateblue', + 'mediumpurple', + 'blueviolet', + ] + return cl diff --git a/src/Search_2D/queue.py b/src/Search_2D/queue.py new file mode 100644 index 0000000..51703ae --- /dev/null +++ b/src/Search_2D/queue.py @@ -0,0 +1,62 @@ +import collections +import heapq + + +class QueueFIFO: + """ + Class: QueueFIFO + Description: QueueFIFO is designed for First-in-First-out rule. + """ + + def __init__(self): + self.queue = collections.deque() + + def empty(self): + return len(self.queue) == 0 + + def put(self, node): + self.queue.append(node) # enter from back + + def get(self): + return self.queue.popleft() # leave from front + + +class QueueLIFO: + """ + Class: QueueLIFO + Description: QueueLIFO is designed for Last-in-First-out rule. + """ + + def __init__(self): + self.queue = collections.deque() + + def empty(self): + return len(self.queue) == 0 + + def put(self, node): + self.queue.append(node) # enter from back + + def get(self): + return self.queue.pop() # leave from back + + +class QueuePrior: + """ + Class: QueuePrior + Description: QueuePrior reorders elements using value [priority] + """ + + def __init__(self): + self.queue = [] + + def empty(self): + return len(self.queue) == 0 + + def put(self, item, priority): + heapq.heappush(self.queue, (priority, item)) # reorder s using priority + + def get(self): + return heapq.heappop(self.queue)[1] # pop out the smallest item + + def enumerate(self): + return self.queue diff --git a/src/Tello/KeyPress.py b/src/Tello/KeyPress.py new file mode 100644 index 0000000..66e9f94 --- /dev/null +++ b/src/Tello/KeyPress.py @@ -0,0 +1,19 @@ +# @Time : 2022/5/9 20:49 +# @Author : 2890199310@qq.com +# @File : KeyPress.py +# @Software: PyCharm +# @Function: + +def main(): + keyPress() + +def keyPress(key): + if(key == 1): + return "e" + +def result(): + return keyPress() + + +if __name__ == '__main__': + main() \ No newline at end of file diff --git a/src/Tello/KeyPressModule.py b/src/Tello/KeyPressModule.py new file mode 100644 index 0000000..bd7182a --- /dev/null +++ b/src/Tello/KeyPressModule.py @@ -0,0 +1,31 @@ +# @Time : 2022/4/20 12:27 +# @Author : 2890199310@qq.com +# @File : KeyPressModule.py.py +# @Software: PyCharm +# @Function: +import os +import sys +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../../PaddleClas-release-2.3") + +# import pygame +import Tello.KeyPress as k + +def init(): + return + +def getKey(keyName): + # ans = False + # for eve in pygame.event.get(): pass + # keyInput = pygame.key.get_pressed() + # myKey = getattr(pygame,'K_{}'.format(keyName)) + # if keyInput[myKey]: + if keyName == k.result(): + ans = True + # pygame.display.update() + return ans + +def key(a): + return a + +if __name__ == '__main__': + init() \ No newline at end of file diff --git a/src/Tello/KeyboardControl.py b/src/Tello/KeyboardControl.py new file mode 100644 index 0000000..6997c9f --- /dev/null +++ b/src/Tello/KeyboardControl.py @@ -0,0 +1,105 @@ +# @Time : 2022/4/20 12:27 +# @Author : 2890199310@qq.com +# @File : KeyboardControl.py.py +# @Software: PyCharm +# @Function: +import os +import sys +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../../PaddleClas-release-2.3") +import logging +import time +import cv2 +from djitellopy import tello +# import Tello.KeyPressModule as kp # 用于获取键盘按键 +from time import sleep + +# Tello初始化设置 +Drone = tello.Tello() # 创建飞行器对象 +Drone.connect() # 连接到飞行器 +Drone.streamon() # 开启视频传输 +Drone.LOGGER.setLevel(logging.ERROR) # 只显示错误信息 +sleep(5) # 等待视频初始化 +# kp.init() # 初始化按键处理模块 + +def getKeyboardInput(key): + image = cv2.resize(OriginalImage, (Camera_Width, Camera_Height)) + speed = 70 + drone = Drone + lr, fb, ud, yv = 0, 0, 0, 0 + key_pressed = 0 + # if kp.getKey("e"): # + if key == "e": + cv2.imwrite('D:/snap-{}.jpg'.format(time.strftime("%H%M%S", time.localtime())), image) + # if kp.getKey("UP"):# 上升 + if key == "UP": + Drone.takeoff() + # elif kp.getKey("DOWN"):#下降 + if key == "DOWN": + Drone.land() + + # if kp.getKey("j"):# 向左飞行 + if key == "j": + key_pressed = 1 + lr = -speed + # elif kp.getKey("l"): #向右飞行 + if key == "l": + key_pressed = 1 + lr = speed + + # if kp.getKey("i"): #向前飞行 + if key == "i": + key_pressed = 1 + fb = speed + # elif kp.getKey("k"):# 向后飞行 + if key == "k": + key_pressed = 1 + fb = -speed + + # if kp.getKey("w"):# 向上飞行 + if key == "w": + key_pressed = 1 + ud = speed + # elif kp.getKey("s"): #向下飞行 + if key == "s": + key_pressed = 1 + ud = -speed + + # if kp.getKey("a"): # 向左旋转 + if key == "a": + key_pressed = 1 + yv = -speed + # elif kp.getKey("d"): #向右旋转 + if key == "d": + key_pressed = 1 + yv = speed + InfoText = "battery : {0}% height: {1}cm time: {2}".format(drone.get_battery(), drone.get_height(), time.strftime("%H:%M:%S",time.localtime())) + cv2.putText(image, InfoText, (10, 20), font, fontScale, (0, 0, 255), lineThickness) + if key_pressed == 1: + InfoText = "Command : lr:{0}% fb:{1} ud:{2} yv:{3}".format(lr, fb, ud, yv) + cv2.putText(image, InfoText, (10, 40), font, fontScale, (0, 0, 255), lineThickness) + + drone.send_rc_control(lr, fb, ud, yv) + +# 主程序 +# 摄像头设置 +Camera_Width = 720 +Camera_Height = 480 +DetectRange = [6000, 11000] # DetectRange[0] 是保持静止的检测人脸面积阈值下限,DetectRange[0] 是保持静止的检测人脸面积阈值上限 +PID_Parameter = [0.5, 0.0004, 0.4] +pErrorRotate, pErrorUp = 0, 0 + +# 字体设置 +font = cv2.FONT_HERSHEY_SIMPLEX +fontScale = 0.5 +fontColor = (255, 0, 0) +lineThickness = 1 + + + + +while True: + OriginalImage = Drone.get_frame_read().frame + Image = cv2.resize(OriginalImage, (Camera_Width, Camera_Height)) + # getKeyboardInput(drone=Drone, speed=70, image=Image) # 按键控制 + cv2.imshow("Drone Control Centre", Image) + cv2.waitKey(1) \ No newline at end of file diff --git a/src/Tello/__pycache__/KeyPress.cpython-39.pyc b/src/Tello/__pycache__/KeyPress.cpython-39.pyc new file mode 100644 index 0000000000000000000000000000000000000000..3608c273562197b015319bf3caa884701c678177 GIT binary patch literal 564 zcmZ`#!Ait15S=vLZV*@YBSfgM74#+|!s1CN3-u%mrEcaRn{Fl9Jrum@&-9ma_2e&j zawb|_!A_dVBr~0P?^Tn@0gyG*_VHK%yz^z>BD&nrcBkYtXz>OQpd&5m6gt);IwO=i zSx5E+;S~hvaRI4XQT-pI?l7nAc;NQC5(?-<-U+YP*e)zO*MW^GAKWM2UM?4v)&}RM zax;qtD~Gf5>|*Ho9*t?vvW&lhKSRm#?q^>1-1@k#o;G8K#%w{@g#3!}_Qo;i0{$rl zFQf!9KGab`st{k9e{hi(7@()ZOQQ74#f~UzB{`<=m?H=!!ppE!41}dBz;buX81{Mw zrMR(ANV}cc9#Pzr;5lBEC6g=5JdFdbFwpk7O;uxA{@YPq)s5a6ybi)BYNn)$X^AhT C9%SSI literal 0 HcmV?d00001 diff --git a/src/Tello/__pycache__/KeyPressModule.cpython-39.pyc b/src/Tello/__pycache__/KeyPressModule.cpython-39.pyc new file mode 100644 index 0000000000000000000000000000000000000000..1114802427f189c6218d58751d955cb5d2968986 GIT binary patch literal 657 zcmaJ;v2NQi5WS;hiFNG2LxD~Kx_XETG+R*=1%ggRjR4I=7!{cC+A5}HLsSM8$&`LZ zhj{GwWaFACzmO?M1`af&J?I|q$kXGyqaKfkz;-j~PW}jh+mQ4v=j0>1`^I3vpau1~ zqC&zmah(t_rV$5}ZE%A|yn+qlV_m+K>IKJ%Nq>VHnt{o9-Jy}m7ot%#yaGPOuP~K& zda?Y$|A@EvJmEFD_y_8YRK9qqp@4o*W+-;k3-c9$|3U?QCTg@(K7!TsXXyZQ5k z|Jpt#Yghl3GLI$m&(s|?y(E?B+Vz?YWIp>rEvuPu>@o((Mwp5w zJffFnxztr%mea8pE9Vo}IiId|`_pH7y{6ju+*D1?+&HGw=a(q} literal 0 HcmV?d00001 diff --git a/src/Tello/__pycache__/KeyboardControl.cpython-39.pyc b/src/Tello/__pycache__/KeyboardControl.cpython-39.pyc new file mode 100644 index 0000000000000000000000000000000000000000..aad69a24e4494962325000aa82ae17fa4da1fc3e GIT binary patch literal 2022 zcmaJ>&2Jk;6yMozf5!Q4OF!IFw{@kY&>{{NP$b7~BGM#sQWZu~t&L~wth3&AXD11E zy%G}q0lmV>=Eez$KYKo>|koB0L~6_&;8Isvm@mYM1CR(rH^CXKekSTnT{B4Kdqd4U{+9;Ka;0n6%0E}lHH<_TzJXd#0ct_%=YxyE&w zM}!E9RBl8XQFrx7kBrESETTnrUm^N|$~GY0B*wtv_8>t_u*sn^REMaKWabcMLDXYz z3{tXwfNj7&;PeD10DnZ1z^JB_NQa0Nc%F?tF-`*>Ot1m-8NgqitdO28c)p%Qn1H7M ze|HigJvs3FbmFnVGYy_!Cu=M+GqC!aJae$wp%U+A_GC9&lz@Fs^-(`T=6H@zlX*Tf zv|v9rNgk-r5PM7(fI;sYeY0;3^;7YS|A^NHvoE5g=HN8XY>e(f`HQ-&zw$C85bb4G zO1DDa=`1~smRp@>&n&DK9u&5P`fv;DE1Qot1Zs^Wfk2)>u0RI@9Sal+ruU(&*!<@rhsloJ-e`4Dm*9^wu|aW%40Mqlha=0HTn}A zy=-FAEegdQu!oQ=H_(B%(F33&3|qteqmQBh^nlH`UYnG;(5=(aE!4c#6UnN8+4 zUElH6+D?;-blGWB=F}d!gzt;Y1g*x23S)%@KE;;XK4vbb!fXVr?Qo&X#DyJl)`&+5 zFQ_}79Ab+*2Q+9juFTchA<$l8d_ww)V$eX|W9_{W04kP7p#><_q$ideC zcCY!c_cM?{SOue?9Ma)UBVD!8MQFBcnhib^MlctT}eRFvm;n@i>Mzx?oK>2CA0Pv!IdUC_*nn^1%xP~R+cr@Zn% zt2Y;GB0t$%zD(g%Xz{vGgHUK;Hxzou0VSDErvnEkEaEaBBql6pFN|mGTCL%Fv{nXC915k`@RJirDEg*nq+`FxZIe%Ff9M3v}SqI>%Ce)M*DkHrF@r->+0b zkd&{}BkBpGQmt-Q<3cc5X?9l9q*f@0l~u=YQk>aZTd8e1403}jiqoA6V*#rM+~E}4 zWAw0t=k9H8?9^5()$P^F2es|B2V3iv_t_=MnU|cgaLa)gFm_qutkifzveqCwB8+&< z;0P4907e+`y~C#44)=p&Y#lqUR7R}GQ|7viwclz7lTj+fqd_)=a4yq?@1zHI4oPVo(@l literal 0 HcmV?d00001 diff --git a/src/prepare/calculate.py b/src/prepare/calculate.py new file mode 100644 index 0000000..7182c26 --- /dev/null +++ b/src/prepare/calculate.py @@ -0,0 +1,12 @@ +# @Time : 2022/5/9 8:45 +# @Author : 2890199310@qq.com +# @File : calculate.py +# @Software: PyCharm +# @Function: +import os + +os.chdir(r'E:\PaddleClas-release-2.3\PaddleClas-release-2.3\deploy') + +#### + +os.system('python python/predict_system.py -c configs/inference_general.yaml -o Global.infer_imgs="./Trees/test_images/90.jpeg" -o IndexProcess.index_dir="./Trees/index" -o Global.use_gpu=False -o IndexProcess.Image_root="./Trees/gallery/" -o IndexProcess.data_file="./Trees/gallery/tree_list.txt') diff --git a/src/prepare/change_file.py b/src/prepare/change_file.py new file mode 100644 index 0000000..2c06271 --- /dev/null +++ b/src/prepare/change_file.py @@ -0,0 +1,84 @@ +# @Time : 2022/4/19 9:41 +# @Author : 2890199310@qq.com +# @File : change_file.py +# @Software: PyCharm +# @Function: + +import os +import shutil + +# 读取文件名 +def readname(): + filepath = "/deploy/Trees/gallery/0" + name = os.listdir(filepath) + return name + +def main(): + gallery = os.path.abspath(r"/deploy/drink_dataset_v1.0/gallery") + all_files = os.listdir(gallery)[:-2] + all_files.sort(key=lambda x:int(x)) + # for file in all_files: + # print(file) + + for i in range(0, 102): #创建文件夹 + dire = "E:\\PaddleClas-release-2.3\\PaddleClas-release-2.3\\deploy\\flowers102\\gallery\\" + str(i) + if not os.path.exists(dire): + os.makedirs(dire) + print(f"{i}创建完毕") + f = open(r"/deploy/flowers102/train_extra_list.txt") + for line in f.readlines(): + base = "E://PaddleClas-release-2.3//PaddleClas-release-2.3/deploy//flowers102//" + s = line.split('/') + + str1 = s[0].strip() + "//" + str2 = s[1].split(' ')[0].strip() + str3 = s[1].split(' ')[1].strip() + "//" + # print(base + "gallery//" + str3 + str2) + + # 复制训练文件 + # shutil.copy(base + str1 + str2, base + "gallery/" + str3 + str2) + f.close() + + f = open(r"/deploy/flowers102/val_list.txt") + for line in f.readlines(): + base = "E://PaddleClas-release-2.3//PaddleClas-release-2.3/deploy//flowers102//" + s = line.split('/') + str1 = s[0].strip() + "//" + str2 = s[1].split(' ')[0].strip() + str3 = s[1].split(' ')[1].strip() + "//" + # 复制测试文件 + # shutil.copy(base + str1 + str2, base + "test_images/" + str2) + f.close() + + dit = dict() + + + with open(r"/deploy/flowers102/flowers102_label_list.txt", "r", encoding="utf-8") as f2: + for line in f2.readlines(): + tmp = line.split(' ', 1) + dit[tmp[0]] = tmp[1].strip() + #print(dit) + + #更改list内容 + with open(r"/deploy/flowers102/train_list.txt", "r", encoding="utf-8") as f1, open( + r"/deploy/flowers102/train_label.txt", "w", encoding="utf-8") as f3: + for line1 in f1.readlines(): + tmp1 = line1.split(' ', 1) + # f3.write(tmp1[1].strip() + '/' + tmp1[0].split('/', 1)[1].strip() + '\t' + dit[tmp1[1].strip()] + '\n') + + # print(line1) + # print(line2) + # break + f1.close() + f2.close() + f3.close() + with open(r"/deploy/Trees/gallery/tree_list.txt", "w", encoding="utf-8") as f1: + name = readname() + for i in name: + if('GIF' not in i): + f1.write('0/' + i + '\t' + 'tree\n') + f1.close() + + +if __name__ == '__main__': + main() diff --git a/src/prepare/spider.py b/src/prepare/spider.py new file mode 100644 index 0000000..0373296 --- /dev/null +++ b/src/prepare/spider.py @@ -0,0 +1,5 @@ +# @Time : 2022/4/19 9:54 +# @Author : 2890199310@qq.com +# @File : spider.py +# @Software: PyCharm +# @Function: diff --git a/src/qt/__pycache__/page1.cpython-39.pyc b/src/qt/__pycache__/page1.cpython-39.pyc new file mode 100644 index 0000000000000000000000000000000000000000..54af08ca664089b785849ea89f949364e56dfb4f GIT binary patch literal 4957 zcmbtY-ESMm5#Ku=$slH&H7f<19p($PmA zy?0D3LV2l;T6t+vz(xDggbY#y28yCUfjrc0`fn8XRG^hrJ@>6B>i%Z$NSzofw&J69 zZ+3QWW_EUVW>)s-XrAFIOm&ujGRfFKXpnre7(9>WZ=mChYc8|st-D%7xAaEJN@)?^ zunaYyw$j3=XS!LDMsKP z#%`pnajq?}N_Gbtu-S?pX6Azno)lqjKDgrWRT21|6JMQ~p}#qsb5~q&ZU0#*Tw(j- z*;6y8D_W?1rAD78A030|(fnu731(@WSvuFaev?@#p5g}HMx=<9=2>oHoZ&gBk`K)# zr~0xd8z*bTrT?S=m}vC&|Av_jtqYUUk^zA;PxW+-1$sBN0qiEL8k?+cbkhOM#g#0c z?HNQ58Z*%AW<3}6J^dYhL+|FfskrIgkpWatJVtx0TkI+Gs`1!{PLv8}Ja-VDkUbvj zSHkzDSid|U;RQb0GxqSBQ2I?gM88sZuYRTOu70KNA*_Fr7kRPQ*SQ3{jm2{Mwwi)2 zQ?V}Nv@f62R#QW|OeJ)gg51)O+%n{rW4RNLA-6mvx15k$hTKE3+{3Z$ry+NG;2Q>? z9*WG>(y-6KMx=x zel*=B0ycy81u1Ht3Ge+b{7IEg4$X*0qh$>1`gKQ$CZduIIC*`JPCn3SPS!{M$E6YX8S|aq;^80Ie$5F z8aWE3tlXRwD?&;rQ3T;-`?}L;H;5kk(n}UWCdX(2nfdRM+sFyRkW+-CP*mDY-?am= zFqy* znSkA3?`VOBo^p*I#Rg=q6lF!qTpKD|4e*&B(^%&=awT)K4f9<@l?}a~tLM8Tw=#$% z$Y@a{0k)v9I`*y?A zBLs^_5^T6)B^VOD*cbiz){>TVn1^^SJs!_2j%8amPY!W?ZsDi%?{uloS<<%E9#6P;>5R);J2>*Tnj=XG?ym*=k1y zMvl_2E+*zy7at-&a_IwVVChS9`>XH`h$n{q9e9Wd zl>Z-80pq3DugvbR!Z#tF>axBH4+&rW<5HQRWNSOkD^8PpZ(G^ec=9xOSp_6bRamG5 zPI*2o;EuP@UXI97slmgnsYT(s-c0|TTtM+5J=Yo=La2I1o&*uA)aJ&qYE|LQ8~%;~1`@`IP-=F$JwNHBd8Iv3}|boyG@B z&$j>s(6COIUz8ym>Uw@dT@vF`gfOWACeuwT8e@RT#+dW~W5$@w0F#R`*$AVeuQ{s< zIczXh@@-ngzyA8(y`TM7f!lw+v-O9cEAZa!Pqse%s7*!P*6-iD_p6V$Z{OYd%?I~> z{mJ%+f7<@z-R-;Yw+r<3M?c;9;1^qe`Q_H;$CZ3kMvu?a|1n-@wNOghf#Ws9+@Jx@6+O`|bs3R-MjU{crBuNSB%0pCMq#dThSY5?T z%{*nEFbzrAO3BK)-s-B;Tn*E6>+```Wvb|ElJeL6Q1|@MXxX?eWb9T;G*N+bN0I_z z)?W7240K&_NI&byLQM+MM34w(cERe!wquzA#f<9GB`eSCjvC;?W&{r1h&**WQYt-Y b1-REmCOA(wTA!{Fralf^n%Yy;r>OlOg)L(F literal 0 HcmV?d00001 diff --git a/src/qt/__pycache__/page2.cpython-39.pyc b/src/qt/__pycache__/page2.cpython-39.pyc new file mode 100644 index 0000000000000000000000000000000000000000..f7d7721151b6dc5300679df425356ec7e878bebf GIT binary patch literal 8353 zcmbVRTZ|mpS*}ynU0q$>({u6IGfuplS}==y6+m#uEV%zWdWjVke;b?{m-d${`>!zJ2z)4_`UVm*}3{lit^9Ynfw*dc^gmsHz+*CW1-SyHfyT3 z+SF`~(U=^Z;GsPyN3 z6Xk*^7yYFH8!%5_Q3gz`FNEis%l2~fynUW2_Y}|Yicb}VJk_{ zNi{z@tkE$he=0g}XNtQokLyrmc8?+=e!F*!%CXJxt+MY`z29Xv7cDUo^RD!abkVZ z+VeX+h?AfeTW%~S+B|6SAUQHE{AxLzarC1$9ex8({18Qt^%O_xsVG@bL#ZZOKQ~a& z%Jq~+u8~Je7p($Xg*wd`qAVun3H3_D8l14LJZGELxwH^FF%F!hdhFC&ZkSfGLpsS( z+vmiuwst2vvv^HS5xVi~+z)-w_w{RQzxr9j2g&2M zTlcT6wU1K6ae^pF9On}DikDF+Os7B9R83~8)HYbRB1o||03tx%Vf2)Kk>&?t#jZL~8Lc$LyHa zmHOqLN&-eiY~=S<&JTWs9p-5Cw(`}+G02KHs28zEzXB+2pspy#IU;vMJ!JfEvr}l- zm7YA0c2U_^cyH9hIPDG=nK`9~GivgL2fc&ac*8uwiIbOhRdBD`eMj&i@#0Ov7M2t{ zNY`36v(Ejb!=rVp?IwFyt-~M=65q30+yk@FQu=Yia&^g^T*zwbX7;m-tIU3dh<40avhB|Q~KdA5Rw0N2$*-Fd) z2MKp;i9?5~=J^UOU{1>7REwP`H6s6sLy&^;WO0#Tim^~ExZxMkjjy0k^a?Ap3V3JX zCpk@L3#<%&Qq>B(fVzwt+{G@b-FeAb*$y?5*U?W$gV;;3)+QQt{He;Z3L-O)?dSPj zkYL1YYL5*xFiP$?-&6ZqFDKYULn|*@%v0Y|j@f}pOd*J+b^S56{kHEC5pKRVL8rFM z-KOQQTTcjAiPhT0e70tajFuaDpFznNM9DfH{Ql{;A<#>F_%hBbUZJ1w6$P=1Jr%OOckn~3)M*T|y?1P4zoL-rLa*2}g=Cj{7=>Ja zEioEJ%$tzj64gScxol&s*vr#gb}q~h&t(qJWez2qAKb!QO=6o~VaO=o&WO%C5qQ9Q z5+r*guJF%r%+MmNTf#7aywpg>+_o+mOWKQdi>$_{Lrk%r`+sJ=@qvUE;iTTHr8K`A zw%mljgdTqxMOw@(6}M=RSdae#6~9Qu=c%Bz{4$DaS@7fpr(UHg(n?(DC(=AZ&v5u< z3V)S~U#5ao!VJ4|(iM;K#IK=HiVM&cIsEBt6&fQ4-9fxc8e? z#WSv-QXQm5wBaM{+B0Pr9P6o1VQ(7BZRLbPTWj4;M%P_g8j0s(1>R6zg0U)U{tpS?4*E1RyVg3q5UK58*l0TFv&2XBhks zJWBUfiOxxTuy#Fc)!ZIJbS-L4F5L^A2OO-O0f@;*~YVK>1Alk+12|BRP`bs)y_K%J;Y z4j{bQPUu-XK2FBTw{5n=poVk5lAUo(R~U?P5X1C_AO{wY#S+HjYLq5LCdOsG^_kaiZ?R)F&|PQ!vz@hRH?moZ0Ct)Y+Zr z?K3+GKM{BQh{a^R#Lek$bYqVMF5mrrMx)xEU)#5WT@i$UR(DJ>;tZFKOa-=Cw?3N*AMp;jZ1OeM8`fQjF-A#wWpB?;|7gr&cfmr7 zAbhGdg9wHD!O#H|%HGb4OQdT2CZ21vn*1#+{7XDBSpvmaW;yjTv)E;5>&xu2x{Cft z8BDVA8GTLRnotH5hY;q4@1XQSr2$((xK(A7`r7&}t4;yonsuc<6tAR3qU2w-_SVON zq9q*RYIg0B@UL674(CLy8QVM(>)mV#w5+glZ{lG5H>j8qurFZjn|MaLZ%zu=&%m`+#B%*A{`OAKw2sXYX_ACGs1SU?(b*kyCXe!84kl+ zv_y<=LC;X+EJH~Oq$e0}bje2mXb*D%A{@y!t>$F3DSQG7KGPhT0}NASAT9pu)EXOu zvBn{P;oEqm->Dl+*T{;S6TC1PZk)kTW*9tdLcAcNKSp?gksh6lz&hP z6xAE-N)~fv=i01RC=n33P2X`+({Y+DuM<+c>^KJVT6#2&a(?nHh`Am_hGLqH)3cidS+$8*5wtoe!3gG9a;46U6 z;Crk;FX6@67KXQ9#MokgDLL0)7SO6!8RUk$EMmubYGdtrf}=L>bz!)61!F6KSs22s zQeUp^UnCenpKE-s|9RQQtkJmCe@S@pi{8>x_?HInI*?zXz=w z{0|76&efptxf?zaDb>`h^T2!8J!*B5)TH#utxl4(q8G#qV_{4SO)t2~eK#$SVVr9( zh*Q#h=FzLX{CI7!e=rX2~`s6)&TXqV*jqZ;} z2dKWB&f%R8b{c*y*@XT`b?(PO*XLyA(!!QZT=TosD{bA&aLw<@k%t+^`8zaHL?%BxaRi>b^&kRki;A>0s3#boIeoT1K^$ye<0yUoCu1H`g=HN zYGUHPgiOt?Z9yqoMJeL6jLB>$or4zVZWL2Y@qU0i-1ie#-Zx#UwW0|7Z6kXg-#QZa zFVx`2@B3a_7*38NraRbs0-+)xE8tZ`uYbf`d>w^?)J$3Y$@Ezn$r@@+mjtmogrhdC zxxl&?KAjn+V$A~HkvaD_(DB$Y6x%TpIdD9n;7&9++?2WzaTujd``SQ3RxN)FcNnHL z-_xP)#8(t@hBvF~3)+zHqd=P+f){i-yXbd-3(t3>u6pw|SToY)oN`FE@o@OPK^PIc z=tcpOnuu(wg_%Ic&Wj9|oue-lTzDI6w9VL_(7X5}6#s=MCMi-VkAQqZ8Bh288Kh9Y zZ3-vE8FU2_=J;zU66FMW!i1eDAF8J+;X)`Wr9rNQY_ooTpg=|GC(5bn6i(Gfp>LoR z$t%<*C90n(&k(@Kq=Qgb1T~jblKK9^Kp`jOMC=CmMFGzQe2$V71TRh4hfJEV50MQ3 z#*3RjOO{U=`G-QGjPXPtiCReg{w^rex*LRks&;}Iu`a{pNxgD;25V4CXLX8Dk3a8W z@@=;h`@98o&zyonPH~DUB4JQ`$|3b5d`j{O`;3S{Xp!nuO?9}k_~ymi0DF#)W9}FO zGD$%b^Vm!}>a6?9PrIo&sPqd9ws2xE&Ahp7IvLrhVvx0i7Bh>I5+x+H9tBD0 zOCv~T;SohgU&hA5){PQ8bRanB+4@<=qG0J9VOMzk!07^8!e95&3_hof+9tH_+w`WJ zRNSIMa1<$3PW0lm?Zm6b&cJO<`~#ktcndWA0-W}FPNUU}Y5w8SR`P2C37iNfd;;4% z#Fy%p&5;W<wTg;{uo_9}P* zr(h*5AYKxmO%T`YfCS1_A01Xpy2;edRaoD^1#c;sJ>V9w_I`uGda%9+j$rTZts%Q1NL10X1&oJuNOfvfNZz9JL^j?59tQ{gJ1f-GJU z3IQsfCAokD+9W5~!Mt&zrpb07Z_JsB9nKr)6}l=L`Z6kX|9E&g29KTvA(H|}Nr9&v z<*$;0Km{s7E7AZs589z6rFg2QRhH4H{ga@B&k1;R4R|*>3;4D;4twB;3N4-^25$*X zK%1l}Hc45u0!GjZQE*LzG}IEAKH?JKVTSQOMyP~+@DV{<<|PWfsOKe2BQ#1QEf|5Q zh!Yyaepl2O;4wdH93muq{TS#Ec=~bFV-XV2OL!JZx{D6dLEj=_4bUNGk+gQT$cKEB zw+4-*HAIJ7oRKW=Di1R`(t=zuKcmg|_av;{>>EeuXsd$}y1R!#3M^9|gAtnA#vrwW zfzT8@2I;;GQr2iwzzED|FM|}!L8ga68nn|MgRvb9(mNQ4P0?eJ?aLqy3`CDXy3ZV> zfx&nWgA6dp_*vLK2bmoV0?mNOV4^RB3@`|I3^IKfWPrhB4}&paFy?0=LifX(k2hEc0JzX8w~>?o`9 zih=5OtfN$%akfxxsH3JStCxE94mXCoRAj@{sy)7rIFFIYdpjInR#s%CM|oD+2VdG4 z?RYIKrRu6`)_PQ5(Lj?ZPoF*|w$z>(!W{C)uJdt1DU%j0>WI3ff$Xoo=m?>A1q zdSMa1N0m>gC4EYhRk@_gQ!~@E{{>$*F1R^gnxC$(vl%k$OUeLv)4u>gxCj@6e~KFh znSj=PYxgBC3rJ_||GjV5?!0Y}$D;BPt})=)KC`Kfky2(Z>wfy7tTFr}vy&KWyE4XyP(>a`#u~$J?yyT>tXP*AGlg z&(``-8`$6pWS@bzUdl`q2yd5d} zp4lRG1@6S!6o_}>(FZ{gPU4c>VAsDf($4p`8d}H&Y^hkRLbVi&;J#R?QB%c!tXRBk zmQ;5{n+2aNL|0g>5{<>irILV0#|=p0qS1cx~dmArcagJ!B67E)hbGEo2U?@!%Lsqe!FicH_)y9!^hB zjIHGW&M!cmAcwWYg#&+qAJSJuB%itEl&bFW+AEP+b#HamS5;lFj=No-!1v!M+W);p z$Uk_v`Z;h|gH?VC8zYRSB%>kCtkBBr(5A?EWfqr*EzXvy)>q9Qy zG5Y$Z*XmrX0&jJ8UG`@;v^R_O&cKI`aTP2sX`0S%A`WSY@>Z>T8+f+?)2}gi@N9Hv zcM${V{^Z@+dxmBN`eu1c`Im)E_Mj7!KcIxFJLb6*aeAb?NBIXLVPD6`MI}||uqvOf zS5g*v^x)ivItwT>Imb=;m%?*wh0v`n^q&?YIVo}(r#mUMp*X*R_-4lQYCjgLRmxaa zC6I%As#|jT&HjXsjc)AJe;^)(o z)rB`>SX*9rJFu6qIQs2a145Dsomf9wFfH~JA0v8dnU01RqoFz0oa5FU+i-M$J6k#> zl?%pR{r2;}KfN^MFMqxI_3uH`6t^GXllkcIFipm~=BhPMzQT4e&)nlgrrdNC=H)T} zK?>}rfh|6OKkZ2Q(Ogwm!E7I){C(Jluu5!PLOn>;3O%{An3jdQZw(sCi=rGV97SL{ z$_iGcNOz*>Srw;7B0dIt+WZxl*aAZP#n^kWN*o`LdiMl!wg#SRY##^mGo1vX=NJ*; qEzKPUa#W=<$)F)()8nO?9JkPusjd8= 1: + p_k, v_k = self.repeated_searching(self.s_start, self.s_goal, e) + path.append(p_k) + visited.append(v_k) + e -= 0.5 + + return path, visited + + def repeated_searching(self, s_start, s_goal, e): + """ + run A* with weight e. + :param s_start: starting state + :param s_goal: goal state + :param e: weight of a* + :return: path and visited order. + """ + + g = {s_start: 0, s_goal: float("inf")} + PARENT = {s_start: s_start} + OPEN = [] + CLOSED = [] + heapq.heappush(OPEN, + (g[s_start] + e * self.heuristic(s_start), s_start)) + + while OPEN: + _, s = heapq.heappop(OPEN) + CLOSED.append(s) + + if s == s_goal: + break + + for s_n in self.get_neighbor(s): + new_cost = g[s] + self.cost(s, s_n) + + if s_n not in g: + g[s_n] = math.inf + + if new_cost < g[s_n]: # conditions for updating Cost + g[s_n] = new_cost + PARENT[s_n] = s + heapq.heappush(OPEN, (g[s_n] + e * self.heuristic(s_n), s_n)) + + return self.extract_path(PARENT), CLOSED + + def get_neighbor(self, s): + """ + find neighbors of state s that not in obstacles. + :param s: state + :return: neighbors + """ + + return [(s[0] + u[0], s[1] + u[1]) for u in self.u_set] + + def cost(self, s_start, s_goal): + """ + Calculate Cost for this motion + :param s_start: starting node + :param s_goal: end node + :return: Cost for this motion + :note: Cost function could be more complicate! + """ + + if self.is_collision(s_start, s_goal): + return math.inf + + return math.hypot(s_goal[0] - s_start[0], s_goal[1] - s_start[1]) + + def is_collision(self, s_start, s_end): + """ + check if the line segment (s_start, s_end) is collision. + :param s_start: start node + :param s_end: end node + :return: True: is collision / False: not collision + """ + + if s_start in self.obs or s_end in self.obs: + return True + + if s_start[0] != s_end[0] and s_start[1] != s_end[1]: + if s_end[0] - s_start[0] == s_start[1] - s_end[1]: + s1 = (min(s_start[0], s_end[0]), min(s_start[1], s_end[1])) + s2 = (max(s_start[0], s_end[0]), max(s_start[1], s_end[1])) + else: + s1 = (min(s_start[0], s_end[0]), max(s_start[1], s_end[1])) + s2 = (max(s_start[0], s_end[0]), min(s_start[1], s_end[1])) + + if s1 in self.obs or s2 in self.obs: + return True + + return False + + def f_value(self, s): + """ + f = g + h. (g: Cost to come, h: heuristic value) + :param s: current state + :return: f + """ + + return self.g[s] + self.heuristic(s) + + def extract_path(self, PARENT): + """ + Extract the path based on the PARENT set. + :return: The planning path + """ + + path = [self.s_goal] + s = self.s_goal + + while True: + s = PARENT[s] + path.append(s) + + if s == self.s_start: + break + + return list(path) + + def heuristic(self, s): + """ + Calculate heuristic. + :param s: current node (state) + :return: heuristic function value + """ + + heuristic_type = self.heuristic_type # heuristic type + goal = self.s_goal # goal node + + if heuristic_type == "manhattan": + return abs(goal[0] - s[0]) + abs(goal[1] - s[1]) + else: + return math.hypot(goal[0] - s[0], goal[1] - s[1]) + + + +class Ui_MainWindow1(object): + def setupUi(self, MainWindow): + MainWindow.setObjectName("MainWindow") + MainWindow.resize(1112, 766) + self.centralwidget = QtWidgets.QWidget(MainWindow) + self.centralwidget.setObjectName("centralwidget") + self.gridLayout = QtWidgets.QGridLayout(self.centralwidget) + self.gridLayout.setObjectName("gridLayout") + self.pushButton = QtWidgets.QPushButton(self.centralwidget) + self.pushButton.setObjectName("pushButton") + self.gridLayout.addWidget(self.pushButton, 2, 0, 1, 1) + self.mdiArea = QtWidgets.QMdiArea(self.centralwidget) + self.mdiArea.setObjectName("mdiArea") + self.gridLayout.addWidget(self.mdiArea, 1, 0, 1, 1) + self.pushButton_2 = QtWidgets.QPushButton(self.centralwidget) + self.pushButton_2.setObjectName("pushButton_2") + self.gridLayout.addWidget(self.pushButton_2, 3, 0, 1, 1) + self.label = QtWidgets.QLabel(self.centralwidget) + self.label.setObjectName("label") + self.gridLayout.addWidget(self.label, 0, 0, 1, 1) + MainWindow.setCentralWidget(self.centralwidget) + self.menubar = QtWidgets.QMenuBar(MainWindow) + self.menubar.setGeometry(QtCore.QRect(0, 0, 1112, 23)) + self.menubar.setObjectName("menubar") + MainWindow.setMenuBar(self.menubar) + self.statusbar = QtWidgets.QStatusBar(MainWindow) + self.statusbar.setObjectName("statusbar") + MainWindow.setStatusBar(self.statusbar) + self.retranslateUi(MainWindow) + QtCore.QMetaObject.connectSlotsByName(MainWindow) + self.pushButton.clicked.connect(lambda: self.msg()) + self.pushButton_2.clicked.connect(lambda: self.search()) + def search(self): + s_start = (5, 5) + s_goal = (45, 25) + + astar = AStar(s_start, s_goal, "euclidean") + plot = plotting.Plotting(s_start, s_goal) + + path, visited = astar.searching() + plot.animation(path, visited, "A*") # animation + def msg(self): + MainWindow = QMainWindow() + ui = Ui_MainWindow() + ui.setupUi(MainWindow) + self.mdiArea.addSubWindow(MainWindow) + MainWindow.showMaximized() + ui.player = QMediaPlayer() + ui.player.setVideoOutput(ui.wgt_video) + ui.pushButton.clicked.connect(lambda: openVideoFile(ui)) + ui.player.setMedia(QMediaContent(QFileDialog.getOpenFileUrl()[0])) + ui.pushButton_2.clicked.connect(lambda: pause(ui)) + def pause(a): + a.player.pause() + def openVideoFile(a): + a.player.play() + def retranslateUi(self, MainWindow): + _translate = QtCore.QCoreApplication.translate + MainWindow.setWindowTitle(_translate("MainWindow", "MainWindow")) + self.pushButton.setText(_translate("MainWindow", "添加文件")) + self.pushButton_2.setText(_translate("MainWindow", "分析路径")) + self.label.setText(_translate("MainWindow", "路径分析界面")) diff --git a/src/qt/system_main.py b/src/qt/system_main.py new file mode 100644 index 0000000..e45f8b7 --- /dev/null +++ b/src/qt/system_main.py @@ -0,0 +1,96 @@ +# -*- coding: utf-8 -*- + +# Form implementation generated from reading ui file 'system_main.ui' +# +# Created by: PyQt5 UI code generator 5.15.4 +# +# WARNING: Any manual changes made to this file will be lost when pyuic5 is +# run again. Do not edit this file unless you know what you are doing. + +from PyQt5 import QtCore, QtGui, QtWidgets +import sys +import os +from PyQt5.QtWidgets import * +from page1 import Ui_Form1 +from page2 import Ui_MainWindow1 + +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../../PaddleClas-release-2.3") +class Ui_MainWindow(object): + def setupUi(self, MainWindow): + MainWindow.setObjectName("MainWindow") + MainWindow.resize(1275, 896) + self.centralwidget = QtWidgets.QWidget(MainWindow) + self.centralwidget.setObjectName("centralwidget") + self.gridLayout = QtWidgets.QGridLayout(self.centralwidget) + self.gridLayout.setObjectName("gridLayout") + self.label = QtWidgets.QLabel(self.centralwidget) + self.label.setMinimumSize(QtCore.QSize(0, 20)) + self.label.setMaximumSize(QtCore.QSize(300, 20)) + self.label.setTextFormat(QtCore.Qt.AutoText) + self.label.setAlignment(QtCore.Qt.AlignCenter) + self.label.setObjectName("label") + self.gridLayout.addWidget(self.label, 1, 0, 1, 1) + self.groupBox = QtWidgets.QGroupBox(self.centralwidget) + sizePolicy = QtWidgets.QSizePolicy(QtWidgets.QSizePolicy.Fixed, QtWidgets.QSizePolicy.Expanding) + sizePolicy.setHorizontalStretch(0) + sizePolicy.setVerticalStretch(0) + sizePolicy.setHeightForWidth(self.groupBox.sizePolicy().hasHeightForWidth()) + self.groupBox.setSizePolicy(sizePolicy) + self.groupBox.setMaximumSize(QtCore.QSize(600, 16777215)) + self.groupBox.setFlat(False) + self.groupBox.setCheckable(False) + self.groupBox.setObjectName("groupBox") + self.gridLayout_2 = QtWidgets.QGridLayout(self.groupBox) + self.gridLayout_2.setObjectName("gridLayout_2") + self.pushButton = QtWidgets.QPushButton(self.groupBox) + self.pushButton.setObjectName("pushButton") + self.gridLayout_2.addWidget(self.pushButton, 0, 0, 1, 1) + self.pushButton_2 = QtWidgets.QPushButton(self.groupBox) + self.pushButton_2.setObjectName("pushButton_2") + self.gridLayout_2.addWidget(self.pushButton_2, 1, 0, 1, 1) + self.gridLayout.addWidget(self.groupBox, 2, 0, 2, 1) + self.mdiArea = QtWidgets.QMdiArea(self.centralwidget) + self.mdiArea.setObjectName("mdiArea") + self.gridLayout.addWidget(self.mdiArea, 2, 1, 2, 1) + MainWindow.setCentralWidget(self.centralwidget) + self.menubar = QtWidgets.QMenuBar(MainWindow) + self.menubar.setGeometry(QtCore.QRect(0, 0, 1275, 23)) + self.menubar.setObjectName("menubar") + MainWindow.setMenuBar(self.menubar) + self.statusbar = QtWidgets.QStatusBar(MainWindow) + self.statusbar.setObjectName("statusbar") + MainWindow.setStatusBar(self.statusbar) + self.pushButton.clicked.connect(lambda: self.open1()) + self.pushButton_2.clicked.connect(lambda: self.open2()) + self.retranslateUi(MainWindow) + QtCore.QMetaObject.connectSlotsByName(MainWindow) + + def open1(self): + MainWindow = QMainWindow() + ui = Ui_Form1() + ui.setupUi(MainWindow) + self.mdiArea.addSubWindow(MainWindow) + MainWindow.showMaximized() + + def open2(self): + MainWindow = QMainWindow() + ui = Ui_MainWindow1() + ui.setupUi(MainWindow) + self.mdiArea.addSubWindow(MainWindow) + MainWindow.showMaximized() + + def retranslateUi(self, MainWindow): + _translate = QtCore.QCoreApplication.translate + MainWindow.setWindowTitle(_translate("MainWindow", "无人机自动寻路系统")) + self.label.setText(_translate("MainWindow", "无人机自动寻路系统(主界面)")) + self.groupBox.setTitle(_translate("MainWindow", "菜单栏")) + self.pushButton.setText(_translate("MainWindow", "实时画面")) + self.pushButton_2.setText(_translate("MainWindow", "路径分析")) + +if __name__ == '__main__': + app = QApplication(sys.argv) + MainWindow = QMainWindow() + ui = Ui_MainWindow() + ui.setupUi(MainWindow) + MainWindow.show() + sys.exit(app.exec_()) \ No newline at end of file diff --git a/src/qt/tello_UI.py b/src/qt/tello_UI.py new file mode 100644 index 0000000..02977ce --- /dev/null +++ b/src/qt/tello_UI.py @@ -0,0 +1,97 @@ +# -*- coding: utf-8 -*- + +# Form implementation generated from reading ui file 'tello_UI.ui' +# +# Created by: PyQt5 UI code generator 5.15.4 +# +# WARNING: Any manual changes made to this file will be lost when pyuic5 is +# run again. Do not edit this file unless you know what you are doing. + + +from PyQt5 import QtCore, QtGui, QtWidgets + + +class Ui_Form(object): + def setupUi(self, Form): + Form.setObjectName("Form") + Form.resize(1022, 618) + self.groupBox_4 = QtWidgets.QGroupBox(Form) + self.groupBox_4.setGeometry(QtCore.QRect(670, 567, 350, 50)) + self.groupBox_4.setMaximumSize(QtCore.QSize(350, 50)) + self.groupBox_4.setObjectName("groupBox_4") + self.lineEdit_3 = QtWidgets.QLineEdit(self.groupBox_4) + self.lineEdit_3.setGeometry(QtCore.QRect(10, 20, 331, 20)) + self.lineEdit_3.setObjectName("lineEdit_3") + self.groupBox_2 = QtWidgets.QGroupBox(Form) + self.groupBox_2.setGeometry(QtCore.QRect(670, 156, 350, 405)) + self.groupBox_2.setObjectName("groupBox_2") + self.pushButton = QtWidgets.QPushButton(self.groupBox_2) + self.pushButton.setGeometry(QtCore.QRect(150, 120, 71, 71)) + self.pushButton.setText("") + icon = QtGui.QIcon() + icon.addPixmap(QtGui.QPixmap("tello_png/up.png"), QtGui.QIcon.Normal, QtGui.QIcon.Off) + self.pushButton.setIcon(icon) + self.pushButton.setIconSize(QtCore.QSize(70, 100)) + self.pushButton.setObjectName("pushButton") + self.pushButton_2 = QtWidgets.QPushButton(self.groupBox_2) + self.pushButton_2.setGeometry(QtCore.QRect(70, 200, 71, 71)) + self.pushButton_2.setText("") + icon1 = QtGui.QIcon() + icon1.addPixmap(QtGui.QPixmap("tello_png/left.png"), QtGui.QIcon.Normal, QtGui.QIcon.Off) + self.pushButton_2.setIcon(icon1) + self.pushButton_2.setIconSize(QtCore.QSize(70, 100)) + self.pushButton_2.setObjectName("pushButton_2") + self.pushButton_4 = QtWidgets.QPushButton(self.groupBox_2) + self.pushButton_4.setGeometry(QtCore.QRect(230, 200, 71, 71)) + self.pushButton_4.setText("") + icon2 = QtGui.QIcon() + icon2.addPixmap(QtGui.QPixmap("tello_png/right.png"), QtGui.QIcon.Normal, QtGui.QIcon.Off) + self.pushButton_4.setIcon(icon2) + self.pushButton_4.setIconSize(QtCore.QSize(70, 100)) + self.pushButton_4.setObjectName("pushButton_4") + self.pushButton_5 = QtWidgets.QPushButton(self.groupBox_2) + self.pushButton_5.setGeometry(QtCore.QRect(150, 200, 71, 71)) + self.pushButton_5.setText("") + icon3 = QtGui.QIcon() + icon3.addPixmap(QtGui.QPixmap("tello_png/return.png"), QtGui.QIcon.Normal, QtGui.QIcon.Off) + self.pushButton_5.setIcon(icon3) + self.pushButton_5.setIconSize(QtCore.QSize(70, 100)) + self.pushButton_5.setObjectName("pushButton_5") + self.pushButton_3 = QtWidgets.QPushButton(self.groupBox_2) + self.pushButton_3.setGeometry(QtCore.QRect(70, 20, 231, 91)) + icon4 = QtGui.QIcon() + icon4.addPixmap(QtGui.QPixmap("tello_png/qifei.png"), QtGui.QIcon.Normal, QtGui.QIcon.Off) + self.pushButton_3.setIcon(icon4) + self.pushButton_3.setIconSize(QtCore.QSize(150, 150)) + self.pushButton_3.setObjectName("pushButton_3") + self.pushButton_6 = QtWidgets.QPushButton(self.groupBox_2) + self.pushButton_6.setGeometry(QtCore.QRect(70, 290, 231, 91)) + icon5 = QtGui.QIcon() + icon5.addPixmap(QtGui.QPixmap("tello_png/jiangluo.png"), QtGui.QIcon.Normal, QtGui.QIcon.Off) + self.pushButton_6.setIcon(icon5) + self.pushButton_6.setIconSize(QtCore.QSize(150, 150)) + self.pushButton_6.setObjectName("pushButton_6") + self.groupBox = QtWidgets.QGroupBox(Form) + self.groupBox.setGeometry(QtCore.QRect(670, 0, 350, 150)) + self.groupBox.setMaximumSize(QtCore.QSize(16777215, 150)) + self.groupBox.setObjectName("groupBox") + self.lineEdit = QtWidgets.QLineEdit(self.groupBox) + self.lineEdit.setGeometry(QtCore.QRect(20, 20, 311, 41)) + self.lineEdit.setObjectName("lineEdit") + self.lineEdit_2 = QtWidgets.QLineEdit(self.groupBox) + self.lineEdit_2.setGeometry(QtCore.QRect(20, 70, 311, 41)) + self.lineEdit_2.setObjectName("lineEdit_2") + + self.retranslateUi(Form) + QtCore.QMetaObject.connectSlotsByName(Form) + + def retranslateUi(self, Form): + _translate = QtCore.QCoreApplication.translate + Form.setWindowTitle(_translate("Form", "Form")) + self.groupBox_4.setTitle(_translate("Form", "连接状态")) + self.groupBox_2.setTitle(_translate("Form", "控制面板")) + self.pushButton_3.setText(_translate("Form", "起飞")) + self.pushButton_6.setText(_translate("Form", "降落")) + self.groupBox.setTitle(_translate("Form", "无人机状态")) + self.lineEdit.setText(_translate("Form", "剩余电量:")) + self.lineEdit_2.setText(_translate("Form", "WIFI强度:")) diff --git a/src/qt/tello_png/jiangluo.png b/src/qt/tello_png/jiangluo.png new file mode 100644 index 0000000000000000000000000000000000000000..22b198d3b0479ef457b1e9705f0a85a5f7f45c56 GIT binary patch literal 62321 zcmeFZcRbba8$bRsN+>#Jk-b+cWMqYqz4r(irII){NAJi%MrH4jy+UT8WR<=*-+<*xc|x%ZWYZG8^&qBn#_yNO)WlkHQ*na@kk z@1?l3R901y0_xx&=6gOp1ScOM=#kWagnvFWYefG2wuzYH&qsf;oA`e|p662j`}=7^ z;y)i{lbG@Td_+?MW}N&u|6BBg5&wAl7ZU#<^@kJxH0qy0!9n4lJ^gDN{<)JsocQNW z{{<5`DEy11{@R9rq2wP<{0k-jLgHU2`G*t#Ldk!jBn}GyLdn0j;a@2EhZFxo$$z0F z4hsK5$-lPYUnu#96aPZVzmWJBO8()*zfkgDD2ao@zfkh8ZTJ^T{^7*GQ1V|WiG#ww zQ1Y*B_!mn4;l#gC@-HO*g_3_b@h_D87fRxw@Gq47Ya9Om4JF??(RFUGdDnZaCq82& zf@ye>G37n&RR3fuv)k9MX9n_r1RA`)(T3R_{2H2@n<_~;Zjf2;!8L-3=JY;bVoFWe z$6x|ormzzwhg-?d7|9`5`AF!apLkub@!nv5e%HEAyF4Ylv@1NmD8HXRd2n>pDAnx! zyTh+(t%T6Td3LDB9qh1{U+cZIn&_Ckur(MRds>tgo^^pICm++b+}W9*Z(?bT-Ia=v zJg9pbeg>*#R)*3_0R3wEQf^z_!!d$B)02X}M|np~2zcU)aK-W?E&U19R`(6s*cEqS zUg$IETa%qydc;w6u(PGw&b04?Tp0hnLJb6snI_sKhpGy$Og)C@+z~db`<9b`-^F)Xe)vH#GFw!lfT{L0 z^gI~Msdo?_i!dCV5UqXWQY0jGVBejzeBh6p_AaS7pMJ%!r>5F@6Q`P;&IRF3fyp?I&j!X$A-hLgpi_qRj99TEkbA zf?6#}a)(9u@#c>FDqr@UwHuf{1k)}mMQhOzHb$e{3@LMEnT3xnq0lwJ11U zq-z}k!4H=E*7=@V;mLM`?bwrw87p7CA02Ah|GAI(s+xBI2j3sx-WMKIT3kOg>Dd3e z-pUY0^6?4`u-A&^zGeB+$jn8+jt_YU#R8VQO;VPUd!15%GvG(Dc?4r!+C8+tuRbvV z%Yy*O!y8bhsWV zb*ZNQ;ON(8DU>lx@#N0z{L1LYIp|IVVA*&SkbtcI(GNe=DyFX{DES02xsJkPT#KBv z2b=d{RJb@VG#?#mK)Lw|mo`D;r@l*3^Nj*b|M2dw2AVnhhVrSI+W^+Bi|Z?AL?3!P zuHIl@I>Z{;?==?aBb78o=^|@}rq}W%yuu0lDU8f)_I?gsVZ6P*}O_U4@oLkQV!v%c2FC z*XCwB^!ms*p^M>e&YfEi381+<6$TJJL!V6|V&|?PNjHMQ0`{&3t%@SC%u?JgBw_2`UmoD`k zV`$iQJl>s0NxE)C8s0jyL;i&SK$#zJypNFh3j2r6d6HGV!JPt3uvIW6uxteSgP2*y zFU(dxPww07Z{Ls>KTEDow8?TW3e5pFBReB_G;%fS#_R3cZ#lfQ?0Wj@jPcStn%$Du zsFX6hDrh1GXKN~m@`LU?t3R&_Nl~&tPV-pkJ|kfm+rD5ApmA(_p5WVv%1Th(B-h?Y zJ$(_8qf&Q^{n5`26m|Dvi#?Pjv}3uh-Vub4_OWfPFBKvDyICf@VXDFeZn=i4x z;hyBTmM7@Cajf1QHG1iaHE21$z$|!_?&LNTpnD+J;P&CNpcrPsp}Rtrc5z&DQu*wH z{G<0Xv8dyY*Qo~@hb_ZzDOn`7V&}hkr8ot!aK`xaouN>Sip4(uzMK-ev)Op~V2beq z;NJoXgM3c}v(*D1Yw!JS%iU*wQo^3f|E06XfM)4NRg~E8{rX*d`_k?a68=XEhLJt1 zncDLvpp0AN#esb&)qii`-PJllkUY8V!BKZXy;jopKDgN zzEQBwHwVaz*#A|OFQKo`C8dW4osCG|tBB3V3>Vyg@bNR=^M2Rm4!q6^8pC|d7N&bT zRafNAjYk^lsHNoKJo%D0tKPQ)9%p!sU&Kehud7Y83}w>y0SgSn)aPxwU%RvvdF8Gf zV+^(^s_*0EAJw~?)B{^7@>Xhgl9jbDd0}~M{W6THNfJWRSJ!;XMzO z{-4H1_P(d8qM;>qOE=DCq~F6m)Kt-IYW-OM1x_*si+D-b-L17e`6;g-U%FG57VHe; z90eGQ$mfPKND2K3W=(<0ke~HB|C5;Fc?V$BgROK4e6lyo`Ce6*Q$u%}fSi7w!dft< zY*Vnm2-AF^$tba1kTj7jsiy`ftJrmO=Gk|?9FbdwY z-?W)+9B7W0IFv7>CXL2P`ur>c=P9Rr{aQ1CcK1>NAOp<%ngix(l6#%MdqRYB-KBnL zv-O5ZnpnDvb6!`&(cHOJQO~>k<4ptU!4j4SGb3s=6ZM zZQb*XSrv$3&Lk9j)BotLj=rGYpb%K~CDH3eDM{Y}g8qZCCUuQu&mV$}FZAc$OS0n~ zJhbu~s{9B+1j556KDqfR44Y#91Xh-`$4RJzPK=q^e*9Ftn5&2F`tO%aFEllhH5fm? zbp$%-V=pOW7(tvyZebCZntXASxs8JTY&>9=f%p{JH%mVKt!MfBiWsvG1xzV!&jL!< zf|v6a#wK@B+gK^-mG||OM^lzxDj&>SbKR>x%}=Y#-D5JYG1mVmquqHS@X_CX}kA%&#o#T&`=ow}_wEqMau7u7K^!)5aJInjGOk+5c=G zCxr$-+~fVy*Re`|yL5Ut<6>ureZ5fk{7iZf_3e$L4=Th%9Utmf-N!IQ))7`8{xKFiP`QdN@)9K@B_tThLI&!w_WdGdE9NnCu$XV6t> zRyW5qW>9#zSh>9&q33e$^MAKE0^}4PC+1-nj>CTXp~N;#o#z4xIC8RL zud-rwMcRp9Q!4pc+1+1%dB4QU==*Jo9_E$F3g7n10Tu`{Nsi8ywHAq2^ICtei4E1s zdzV8ax~rhDNlr#Py;R$etPmr(LtME!T5oHQIjqtbICmE> zo95SRSk=%--Nuk{5Hi;VqkoNp^*t~E%tc+Jr_-M59nGcQUtqdq!DMe~$`?R^A2})i zzS3zyh2cMpuCjydMpl5PQqz8uHbfJ}I&J#0Iw>vhoNz7?t99Zvd`NaCPLShJ#!3gj zM~vnxF)A6eRe?MFcpNLi$5Z1B2m-K}c!I>4!JNpRkNZSHq6$r8tkXzDDGzILDB96_ zMO}=N%0DXQ1-c;wy|X-8pM~+p(0IHe6pjo=f1^jt%=;{DDG)Cz+} zLNL5sGxvHo%F#DpO;*+G8Y}j4{ySQy-akTLe7YyI)8vv$wX9A_1o@jJroK7v>_%Z} zui&cClpq}JPoo!t&dCT7Jq99hZytAa9GhM`I1N=)K9=w9b-`W|HGWqCWSw`bpW5OA zLWaUVRm+@FaS*SN}`IVoGpO@tUspc#HQE?~I8*1VpK$KJyJVlY`aBabd*vhn{ zuB9@a<`cv^o$j%+c;B0qRZaZ6H5G-)z_c?mCqla1*=~JvhsNICAVu8wKGNBZ6Di3& zf4O11S+lrqf0W7M>+5WQvn{R^>1yvM(`^ydq2+vwFUcJ=9zI;QAH89~^uWH?jF;rX&O%C*k}6Iqe|ZRZ&rb=Cg2}h&`U3 zsy|X!-P;4}cLfv7q^3xCE+H$rP77BB4iAqS7E8W;vSoW*J(ur@y<8|@8&5?cR)WHs zx*x})(eYpUodl@uhr85L>hr~JjJeHieyJQ7@o#x&t*=yQf$GGDw-@imA7Fit4cmPW zO;I!C*E_&iZ_Lk9rsU+5>t9ZZl~5N9Cp~g>OucV8cs0d#L}Bc!zB~ePyqbJ$r!;yO z#6Lr0e)hxU9bH|AI#i*8De);@GmVRm<^8&RcG)>Ptps!fA^Hr?BRd~{m8W92P)K=> z2-M<%^tMfZj>bxowC9p{Xn8qj4K!bIe|c7kjn%-l(2sj`H2hsfi3f9g85b54Zn=MV z+Ci8nknn5e?|^(^p$&p^A^Yo8_FZODH>4`&Iu>;K)C~QH%Aa)FHdh$>c261XD=hf< zt#^?h{TK+gk&zMd9PQF@xcYE;Ig6UXk#p3b&?md7?nriM66-KDgpB~d*g2YgkFBy@ z?FDX7QEL~4U78PR9$A^*9N22MUi%uK_k}jv&VID6{&Z2^%sQX_keTnYlFU{?)uD<= z@q7!D!^7nQgU)v)M#$+AdM{v>R$tm`disXxQBma9(xVPE{VMc$>mK|d9*o!JvYH5@<0_&mNGNQn7bEzwq0xlLW_HK8wp%5c3rGskTC?kyga=B6eX=;P>U ziEu3OyxHui$+xAuy4UuxMaS%+@y*uVah;4x)5h%PnzTqnH^SRqt_-5dQ?zwJgKd z|8F^YsblziUf_t?i?blvGK{FmiS}4@I{frJej$%Rw>6@EFib{^eki8#QXpZ%bFhlk ztfV$(dBKzkF~*v4gSD2`TK<%hhC_W@e@bAx18PB0&M(1hYwZ4`UosZNwJxW@v%+{_br9Z?M-B}*;wtXN;mP! zi14r_{&~EX&R!LmGyaNJUOYvGuPSotq7yr2VS*6lV*i z%=tepI@(TcQeJhR>0XLoaMxtK@g$TU)yC(j$|4m=n2SGyX?tB^XzA@UIBST#T?1Cd zNL>73MlE&EJG;C|gQ8NG@;{AC)Jm`Mk7 z9qPMU7iE&~y1cLlgtPntZ5orBZ{40CSNqL$YNwPbF+Sli?2C<3vHJ{pyX`|BVbMTB zhdW?{yzustq=o9kuMK0t%~6W8~?R*mQuk0h4uh& zqD{I+`!^PFpjOIvF0#%28WqqyxlfOJYqj06`JO9+p{6-Z#_UB!R!=Pz1#|0*f*CW% zlKO3rR_aCU%+c|V;Guy?$=F!`Fg3z5Z%%|yuYzW$=0&38L);!kUp94U3WmTQ_xu+! zNiAd~u9sEO(7MfNI+j;bRi6ix1J+bLhmFK`0_~Dz#r8VNa+yno)XRJSH0v}$MYUUe zer4qkIk2P!Zpo<6n|(vtofSE>eb6Eu&A2pJGBbwgu<8AAyC$`L*I_X|Dj}jGOO}I* zBJI{i!&nrb0kX++%u^LvbQ&;R_`SeVS7)k7XFQWD~i zo)-;=t0gWsJhAKCca+}BJAQk#yd_aiO-dYkQFK@gC*U@q0QAG71tn7Tn03D6pSlfR z?Ii8?7mI`M<5{~mK}LfplSo#J!e)_j83$EVQJKmR3?Z2!kaDFB%$3<)v~9 zXeoOXSJkiD$Xpi^*`sgijMjwLfG&4#_F?koNBcvy|2M!F^HW0<8`V9k!|X&w;a@9M zywXRL!aZn%n$Y29H;Z$2>BcEHRAJ+_(D%m3+v_R`@%+xv)b6u$La%dH-DbL7fZD+p zJuUs+eswL5!!BDDOhxn9+AJ;Q>URcoq9;p)6%6LYW}D%bh&^FQj>e^fJrHL&>e%Or zII2E1$cTh~s+5Npn0jwjv>IA^4hm+QwLb=Xst)td%;DIaCN46w*{29J75;h$=V5?P zL?JOvO`%|&sERDeo`)S$XLFjtfU_XY+?u=Jj9XSwkr2;1ZaTZ*@b;DB;gEuUZ3~ct2Mjl!!^N;`#gBdj_vN6DEJYeABRRB{jZ#uS zY{;X;JeS%8%KQ6~i9g|(41)AbGt~r_fvU!fESBsIjyHzM=yF9I zIfM)k7Ydv*Vhkko_pD$v9CqG|7IG}E-_A_kA2jvLq8l#Y3Jk#HZdZ#7JOE3kX%E$X>JE6a8M&5hRj~c;VN8u8Z3DJ2Kv!;zW~X&pHLuy zKR^0lr$0Y>$tUB%Kedox{>hK*;Qt4MCqf3`B%}l5@RV2UKKfS(x@(U-O?q3Qskhtj zSDiQIJov3Y3=FV$>7r9zCLb#aqL;ztRseFLPgeE45bN~5=_(rS!OXhdVs_iA+g@gK zGBZyOtlBe51?TFx+qbGFdl?X8*2U;Fe<*DJ`Ch~rD{FDXR`>y%H8<5eeaC5X$8}-QX$-Zx8+wEG!xDMdScRG-h4dONsBl=C!;3s z?_)}fs8VPWfKM@z9tVCY8&;7;2LEkSiygXAd8^5zV>#PU(SPoVs>0HH@ReH^Z3Osz z8U{zCM>u@8MQ{`lzC24uL!B!z=nD;C97*0YFs#StWY`c)%z1=mFq)o12@hj$t}yO? zROEg(9;CV;SrHtc&f|Cq*0bSem5!7kjqC_Rls{hr3T)qqKQL}EWD9$iP84vd=iEcom_8FTGtysaOhBtO`;l}aXwe>*;Cz+ka)T8}fn<=mTwqUCG-1-NDm;#ml*LgMy2l~T)tKELzDNS{f zEqSBseWq?qIg1VMK?9ZsywN)LP#Os!?1oLT>)YR@e%Nl?2pef^&s0lr5Z0|G*0@q% z(8tqkBPLao;Tc^GHd-*)a=&!gVA)GaL%mZiDMiBBXT3uxr>oW1=Wb z1--O!g*^1+CoHZP=sGKXg10_ZC;+{QmlA}sDdRiehyDDvzEYbT7Ow2RY&R_NTA(g4 zG~bvmD6Y0%&W|1mWEArIvcLcQQ0V?xYm^M>*8LBc=<{F4#{nO&6>Smr{A=fKFFK69VGp>}s0W9R7h5Z=}+WYbbAB(mkzKwoOv ztoe~-X?f#EFd?Rx^AOL(#?GwLwcrB>+rr$BCw zpQ&}+ad#E_&t(z3=G?738KDZGHe$)HJn zI*kH%aF8}w~{RWkQer;QccYp=W^4 z%gyHGV>4@$N0iQ|9^aY&IjYZhyl(H82J$4bvhuL~teuxxeo-FyEU=^~0^PaQL7-&| zY_|_~qYmNhirtXfK=BGfw@=u>I(gou!ClIJ|E4(DItXlSJ7Ql}xIC2*2laRWOG5z? zR2EE#8yR>8LS|?={J}m}+W<6rSM+$PVy*jn9Xl(lMru5d@4@f29J1uN!}qWIg~&h5 z9#~dpKDz184x7#5I6f-ZmW|NU$%xYQ`e2A|QvRx;krbg;9KK30h z5lNSFlofK#ajG9VM5!1WERL=o)5;){hl@*wW@FTNSWr|H81{B)9bOvLQN4Tp%wr5U z)S;~mDd(addoa&svlgl*{+tF}dTt;9xU?(O8ZM1I+?40y>^|I?(Y2S>`S!sXl{}5t z{x0{y+u!!~NdgSQ<8RpfIm@-oE<}{~({6Vh*X)!td9C((5#iIdr=qY-*H=(>(_9Uk zMbBi;XZ4Y{Pz(w3x7sokO#6y%@p3%AO+t)}vTZFxqkLCC4teV+;mNY#F$cr>DD=0B z;-39-EKg^36szBHacZPsSAxGh3({0y5x?$fmm@+R*#ewYsdN|3Ihx~(FJCuQ;d!{} zH}#6$cxcsqn5shBb9cr2x1$WoxHX>%^(i{m{J6}q*k?~9w&bCV2$FNsx7%UqhU=Tl z7o#YQNCE>0%a(+IqFBboK#{;6$tDBcbPBDZK6g%v+UjZ`VT}C6^lPERl9v*buuYnE zZlAddo>)0J1Km`zPfB)pyb>fr0u{}S-zFtx8j_cNb}$gjw6|kuSwGiOAZWSqwaan1 z;SOv$_xv$mrS1oZN+$tg6IOdPw{z@lhO z2+GXK3DVH)9=Go#NSeaM8QrOm-%7Jy&$&$~OQzm5?i!dmkIj1vZEXN-2Zb4$*U!b4 z)cY)J`gG4aUjHy1XlQBNH4{zYz)nIOY&)XlM*iSvcHk;x@)8`Cp`*m%LP%0QA|q0k zLnj6yy3&Hhf~)qcFsqB%%~tq-e59! zuJnjZBvycajy9U0U1SOa{B5h}SC1E-BON6w8@_*SFK*ZlsSxyA7&I)lSP=n4fMEOF z57I211^dFsP_7^_OLRb4Rzhlgvub>w0mJl!hizc;l!4At#NHFR4r;3HA*l;`Uv8-o ziN3i_2-$kx!FEeIyVW-C!YZ&P?3{Mh7ta0aCQGGAzU({ck|6I`{_LZj>81h>ii zyIS?IS>o%WA(No>O<8QXf%l!2F{I{IV~UnRTHuG}Bc_JhqN1YJeM6^RS|{J59c1i# zKPwQaD66xiKfOCrivFdm0)cEbIAFXW+u7_c?QFARy%(@9?6M-gbRbL{kG(d2yS*A;VdpNHHZmq-lKAK^`jr&$J+ujR8l1)MmuUM z#Bbh2_S^xH5e8gF(oQGjy*Qs9`LU0iZNP&1>zR2W#6~}*b#dC;oCMmO3VvQj*XEJi zMCMkbco6@vf@Ia3w_IxaX-{znk!UXyRgBqE$a9syJF=LeSNn^QFe_kGSH*!JNDH>= zd7Ccpof8i77lpWAqG%gH>dBq*e$MIxW6&$65F)5Yi$+r) zc(Gf7bqmuyB$L=r-WJ-t)Ca87TZpyp488nc#OXS6%fLO81qPh9)xnqT1j?YNef<5g zyTXgCF71aT#AYu5s|ITT1`lSINXN6e-^Klr2zjmi8U(G&X+O>P=-PZ%Gj$5JsnbvX zH9bnpTZK66Cg4902Q&}`;2nLE+Mj4r-{B0C!>7#v!ak=3+-x8ZiMLJhn=2{T&bC)M zU~al62{1pzql%`IseG$FYL~p&a)5uiliZk~2HF-d$D&TaiZL3Q2 zbj!iyUO4P)gz15pd4Iu1-$n4}1Ledw*FnOZ$u?lr@%y#LJ^m$;NlJS|sY~j#L80-f zUOgAP1(=1+)5*Zif#9mlZI&(?>hSDPd8z-ws)TB7pF8>yn%~=8B!?+#=6I+3*!WPh z#N*yXx4O0p=*QTPHySG~yF4$D9R+Nb92s!;z=U~a5&C0v0LuRZD3?Mw%VRE8WJH1h z8gXCH9*Aj#$v%gBsRF|ic8iaeMmk}8mG92N=%``S*NRxF)y1so2mBv2-e%Y!3yo^_ z{~L}I7rH2<`foiI%72bm4LbqT2?&2~-flYIMc!F&%k|kZITu4YeNt_Y^ zh!oP66x#936Qj4!)&K|T_}R>L9TM3BOHO=FiLx^3%vk@ln5nn_3B8+2sgxh5Bj?M_ zF#saCaGVhtlX|=LX+RrFcnaVg2;Wm$$4Lc1G?fQ3rmTH22<+x6Q*eXd?ilih=0%p8 z;JAaSVX5>t=Mf0pwJ45{!L@aSqOtFh`{`H4y`>VP^X&wD5(cdy`Ywy)G_+^ClJ7>E zWYSQ4)#s(LvGaPg-Z+i_d8xy-BPHH@rkU_`ZfMZ-5__N&Cy!oh_sZ_i#4>bP7JBkS zEcs;xo^Emq5zO9te-Uh0T*( zO=^4|v#1bn0Sm+gU6yg-tfzBs_4iI2dwUm}czY@cPu2z~rbTK=g$^rrsHrPbg?7i+-mxV# z8^9Xr>A)fSdoJ6!``%**GJePyTc?h)rLC-*DPq(Wl`LV+4^L!qQo66n!jc2x9N-JF zdYB84Cv3*y^5R3p)i?7ncS|J|33a-Fs5Fnh* zF=n2bfGaA*6aYV4N)yV_*RV{XyU} zgRaTRk1@g5t_@VUWnu1>hX2yflbm_19hyT|Sa0pCkR)({AIo@;hyCZ&(xxj_XgRFk z%|iBSrfJb?O)jJ)-uIC`xVt=S`*lSH`zRGrg_yd_Dp`DvNJje;lke4 zG`BpTh7xe04jf<4Y^A@5G=*;)ZeI6Sf0ky(!iABEyw5=v3n9^SL-ESJ-iK211Ox`p?P44~G_xDB! z5kioBk>-`IN-lX;0B8eflhUPtc;A5RphA%Z153ubTw{Xap=_bw-p;Kt&&dEWm)!-i zy$ZqRrQl!=OHG#a$`ioub*O1JFAdyPV@O5EFMNrMPk14eqoL?LMDHaW6u59|o{!!r z9nK>erM;7V?PYQEN0L4%J#5>wBpp0X^us)wiel8DC|smu_o>lVMr&mc>sTgw= zj|rq8dS`OLG`74eD+-hcX>bQAm;ywt=hK>P&a3q6u63XeHUR(fILr-MtS*)<%>ae- za;8Xwv!bf7d%1`>(3w}x8kcLNPDJrvo;tKq-5=@O)Vs9bE@RR6h7crMffAD264IE) zQ+LNBuQYW4Lj~eG_274!a5qt(ker_1NB=}yPn4A)B4SZlWCtFB! zTylK)h)_Qa(enPu@r+uUSh9?whuGDI@V3!W9i>b~9S!nacb@c}3i=sCzr!HRlOYhg z=4S$`bey(>(Q#7Z2+gU39~?)8a*gXzDp`&z-t#xea=P#$x$GSA`8#DXkmr+;od(Y@ zGKoc?Rx5Z=4SaCysT&Kj3u(yZ8?Nl| z&Fz&=<7jyFT79C|qJhcaDAgHID z8>G`D7yulGF~}oaP6z1|KGy4Ry6^_0%3l1Qbz;&{^tUzgVDtK+vFjqBW@PjM-x`1e zeI_gLbh(z8n0vC^!J)@JXpWzX=CZKuClj=f5jVZ$dmR>5gF@pQJ2}Ke{I7Al$|^*u zl=vPHt$H@sRZVOfft-M6dL;Dt-k1)N|9ur>#og^6Gixuqk8CEoRKdR%QTvtG@Ne_0 z8G%!l`>l}mH}kR3z@`B0;U=P>APFwtYdd-4jiZEt1pcG7119K^_;~KFr1%3dm${Kf zIS>K~y$^nAR51$cWGs7$PZ zG6R&)fxP&`H`VhB$jlAQeu%OS=$7)jg53;_U>B#4xo_3j7-%5RUs;{>c6S5VrFk_o zBO|Wf4w`H_exG{l!STc^q_)q{q?#oVbJ#XDUxsgU2-uN+hSZUTMuilywsapISR#7x zE-;YzG^v4Gp=YJu`G*fnGih7%QUi=T3)1GJ}l zZ{9IC)RC3q_j^{CBsxYrq$IiHXwP+x-ykVDctMwom)tlTu6f?~Gu*Qd4LwClbrwpP z8WH^#yRCR2_tfgsH0x*UP}Or4l^$}RYG^e1jqa%9cY@p@2(KLOW%X%hheMHEfE~2M z$r6y>GaOPsx(HY>mEPf@ya=WBN}=TZgYkNl|B$+k3(Y60rX-Ujh-4XaZxWc98DgNf zW;ka965pV|ONAK3%QAIuhQKHKlDhoM^I_5-1hMU?18egxiD5aOA7$bCx4VMwg4`04 z(EkGn>#D1Z2k`EQE|{5HHNzuee%4?|sm> zhMkZZnk{tU;pkEEb8F?Aijp9ZWdyl?Gb3;`t;@LR1sts{)i)@-iAmBVy*7zs&>|x%eYOd%pWzVSg;erf&^&CBuSP6U_XJor@p$#mFMGyl4Nk9%# z07j8)f6oEpE?DWFX1}yO&{cxk2tbXcjrcD^9L!Hn`TBw;19ZZMB?kZ_S+H>w{MhF2 zq9C;a(N>BgAvEw^w6<`ai{=CykgyC`(&5hE4L{bH6h-~siIB3uxl!5hupBZdk_euE zJw*a4QvbVjb!2bQ4o4zmWJc5#P;LN_jMc%f(c{h9VW2Dn}GHo*?KBpgey>GC!#nf z*uI?uH1}i*7nmXskUu zZ9P${(38V?a3jeQUgJy%7_7y2BI0LzJ{Sn{1aroCHOGe^q!h&{mTwLDYHkFVk~Haltrq9{)jy@2XGh50Hk0 zSG;r24V(b`*K9y}?@V}p^pw69ky-Qs88ruP*t`Id8zlf5+C=}tlet1>awGa~KLM<> znyLF^Vj{@wIs4=Y9egCn&=fjC+^N9eP%MF-T1nOw&E#i3e{Bv#cM}tRdW)X}cf$FZ`*}m(k>7TGhtP8L(&nWc`SOYYA zCt^t-wi#(G06LmN(G+%MGUiyD@TlVpU!MT;26=*_sMd4yv8tuBx)hfezD-5&@7ddH zYBUYF*BgHp-Won*8-TlCCq>u3_}$y!D^|b#^W|L_RUfl}Dr%NTQH1orc3yWRzq~h} zle+JgBz~xOjgJPA|LlGvYua@4I5!%YdupI>+^PCkC&wr+DR#e^7-)n zFx9L04WQJ27ASwJ9S_H)gT7MCrj8q=zTTuZfqq|He4>r>)z~--l zin7jpZtM*C(ef*j)ARQme9Q~Ieze;(&n~9y)CmQphJRW0$t+wf0$$^hP~G9zuhG>{I^g!5@G7OMQSrhYRUMpKmzOzb}nD~a;Cs?>$%ZU zzGzHxrY)%Hz^U>)7^4qv0TGBJ4MB2}toN6lrdrbiW$dFTq67en+BjQZLc_`NhL?k1 zO(j=}$I41aE?=jy@lAjtFNfZA$B&#s8)feHQS3v^S;*7gmO%E@33@(Xr2rqdVL-@MS0!TC>NdZ2gODrxv2w)>Omdh2))lm50godYOc1njFJINku* zH7esj=mfbOCN;34F<6m*3S>{TFz3NApapDTWY3a@hI%V%e_;Mqowg-#v9Pnf@7D!N zk8cSr-{#|`)dGhYbI%V68XY+MIMW$H#Gr(;j0S6)rLS-25Dk<^UD^L#zbkmW94aC+ zFBe5ojV6Gr0y;sE!*yU{^4B%93yE1<%`gf3vDm690j>Nn>-sxSO^$MI@mx~YN@nI0Sx8MtB?T3wh`du zI+Fki!5-Xv?1KEOGjlB0)3@jMWJ+s>M#$ zK)`FjM#Bcqaa}|>g`$I-w2kn=ZaBpHXKAbCGGzsD#@M#9woewmfV3^M%iucwG( zUxIRs?_B`V;R)|C^@yx+{GJei4h#;b?qH%o;bRAG;KeiHcnE4g*{8;xnbpq+2DSzR zVOlh>p6pi|8qZ%>E{trh*BBnq?rHdhL*Xd&ysB40v>P%U@0GMo~Kz~%7SeCcpFb# zlrtQ^DL(>g1((12E+VReM97e!Y;>YqTJ(8_ble<0vSbP|M|~?#i%Nv3@zP3x;s~Q* zl%Z=x$X1D)0}}qHy14=;5>f^&Mq^HXBVZ1bD#L02d2q3CVBT=Nv;sfs03E=L2I6|= zz)OIx2#@17c@Smnj=omH1zu@nCqS_BxrxAIW&#YQ8vxHk+`3AhfaKdaLpCSBDO(i6 zZ$^l`C7m+I(a!*^Q$@}c0UV9Gn>1kbJ31T{%IvT*`LdTSb%F}do)R?zT4&*lR>>0r z*&&cQ4MZF58X1GWFc~MIC=RpNmgcG#u38*~2d5t)@j+Yz#{{TE zf-1Rz{cK%i+KF5uoxrbqE&(Rl=VgJM%1I9hzqQldhdYxv9Fh@!T!)1Omz=k*8mfWD zu&q$+i@k2Xl-$U9xyD2b?0?mDPA*{-<|b0@XO7o{EU0DH5@Lq|#Xy1l4}rA&=X%d% z1-N5JEL;0qHHHog6}dS+Y;cE_9-&Vlch=wC_4t)Ky5)AjOx?g)@ATs4Ir6B}8$hEAi;hfJ=H}!;`z&Z^J9kePBu2eK=Pz)+`2ItstVrOe6;CXw5`!wV+6qZzN{b`D$TBwB$} z`My^VdT+>$n{wCjAlYT0h0wsqQz|4A&Xs9*20?5hDXX3`&t&{;P(3>U!E;;_E z-McmeKoxK$ynL3hfC2E{&K1<31=*$}KqTRN1$hC2cr!tBTci+dlPN)8(W44^Lxl&V zvxMNfcpP;ef)ZZ98;66JQ?^bDX9J!9CPr$ifP<*3fmX__Z;28gKS<>f$gVu?1tq$TV8X&7A{nf}W)gMe-mBqqQzhdTdiB z3pnrCUS@+>Gc<1U1?7@DF61TUJKU@*Y7DG&^GIpPMB$_bjhP5w%T2LKfS7HGiGhAW z%|rU91+Hl!G49HFM53-8UfNalOc$h1f7_G^F(PR++6~HRnFJ%!* zdBWAWf`igi#lf-uDlXPX%8xgRz}t<}6iKAAp+JSx_=!`5mm|={@DmE8B&A8;;XuH{ z4W?{P=p8c%pRBejZA5G z9T_Ub7|_7&p&$Hr5W19*$!j1`RXaL-y~3`n03z0m?{-X(4!F#uu_BG89-}&<5#d9> z&wi(%QCGi!Mk7H}sFpWu9vT72WCW-~8*J$C`MZ61tdtbSbw1ln3Q1glVtB5E9Et@Q zeA#9o9toQj^{)@L>qL3MTaaYX;O?F8DwU=JDo$0+;|;4kZszz}@D1DSBW)S~m^03T z5*K`C{ry*vLp@&kULG&G^} z5HIMr`yf3RLQG(lOdzWZ+$u9G8K~EJH(Rff7ukX~%^G0rAfw7XB$@lIrswZ&Lq>4M zEoM8gt?a!!2*!=zmyV#P4=k3CYb^tdiM~7+ zFVQEff(MGj13^S0**-eydjcwWq$)fz0r&Q>CYTsFz1VA{P%NmC_53VbGE(r#)#Jx@ z{f!482e`Kk8Zi5x9)y5aGq6P3Jq8de>fQq6VZehE$iLQDPwg8Gf?mfC@B1FuIiU*( zb!Qn^vC@H?pmi0LBOr*q7qCTOZb+P)6B0fH&YKOob0JxIz#oX2rw)5>TS4{_wvbN zF;muZ+B|q|41l`l?!cz`8VCWy1SdA2pD;C$ILI9Iyrlw3p*B#`hoC2!ptsCd;cN%0 zP&NKk+C_jU;Y%=Mp5PcWuB`^;o`YAr%3!=r1Ug()6qSlO?zfoQqPglVrc$mLP5||M zRLSDjNDhgYCz{?I#!6?COYQ^vEu+*VbE`>j+7);}YPe+>^1tsnt%>cod1-4{QBrp; zBuBGl)bLSwWw;2!I7WgFY>*9}m+B}Oe3G(kw(hv($(y}>q}#zLMV0kM7t}1VQw7Ci zo5u!HTmS%faTMKUR>?w^b8$`o{A~Hc#*#5~K|Vt1UduaE0QNU}FLa#!ZW*1j4d~mv zt0seWP{a1ePItVX(UwH|{O}UJbTq)^sxQO~L2v9%RvT;NY6eBR@#C#HaW8HOi?XW* zP9DfYGt@(cM2*W3M9oXXHahy1>7zdHt$SYA?CQO*WT$?kEmtDD<%}5^-%0@$j3W(t zL@BVKeBI!`N(r{j(&0e@rW;j)r%-aBFT8%$md~&`gs(VcQ1H0k=%~z4@gUkzX{b1n z^l>qGXsDeOe;eE)^P;jfTH{xx8SNRT!1^iS)0+!>NOD@&LEsU3C7MClk+9Co4|taG zINd3#ORY8jvu1Ng>F29^$xe!`p%OM*&%rhYmgkL4y&2f>p`L3hS@5Bxvb~j6M@(N2R3uRb+sjg^uI(uDs&Tu zAmv-IYT9Y#{=AvBkQe8*KIS~vmL4bZ+o902dC__>^t!@W{vg8GU=|nv;mp2{cy31U z?wCx9QAiWT1=0=*3muy}!$L`h;FX~ju-3U=pyQnx=n>fZrh9V)KXs;<=QU0y6n}QA z=QRWKgT7xLx9v}|EYXIy?izqc%8wagJW5g7GotwIQao8hxFT-dbIUd{6jW%^s<;f~ zn+Kmg(h+C>ORYv|d80Et_7&9p<`b_T4PYG_)-gs$ed@hyW$LBVAqA|arB6nbfGHsi zDZlEyZj|JCXzDx{>~w4G=Nfl(2qH^IM3YBv!x}6Z0wdG2swm%(4-hJHv00wTX0FZM zX8mJk@7naaUgwEyBaoM2bKKz*hGYwPQ=~82r(B8D$W5bmITvQqhEnMM_c|If3r!iBSnl(H$sM{pxE~w_+O1M zMq7=G;H>%Ctpre{#scV&0ZQE^i7ko~-}Io$(a`r6`P@v!YMo{g1Y%tQ91ra$wj>LM zZ%_(Rc6U%yri?QcSZ;qcn%Fx66=O$g@G2xh8Q5sM2tQGy?n42qh{agoHq9q@Vt_xfS|foX`mYB}JuHLHg2MtYnd=0@+@tFTh98At2ceMh!3{#!tH z`RRHg(|I#jeZMC<&wa1@f2g|dK&tomf3zqe3E4%VkOtY~qPVFjd#^-ERwvuhu##0# zA|uJ(*{d?MWfQWqSN1r+=l#*W_xt;!d%xfAIq%Q=^Sqzu^}L?(e$IP`1&3G9vQE)h zl0)GiSDlfpT1ssKMj{AD{Ej+(`KYCW0W?{w~a}kcG}{M##Nl{or!X} zBWAauLrNh=^LZ$TQblVntA8j$rrVle1{LOZQknuv~w&d-I^@lO9sM$x`FFyE433NO- zGZPND==29l>(oKOI@V3~a1mSXkNThZ&p0nJnT!bXUtuA~xi6jyelP5J`gVXg3sMq5 z>=bw*U1*e zpKw=%N1D^dj(-!jvo;8Kv?bKBN-dxu8@zPS~8aS)Zh;gsp)A-Qsvn&CY&Nrw2r( zuhj+rWJQun1gQuY&khLN4JT+W7N_|N_HT5XPinptrNc?ro{Es9ZrLbhHKTOnxefgc z+zlW7RsCnYJ41ybdU{p=6fA$?S7j?n&5gJ3e9(Sq47Oy#9Y=jyZD8iacXU_@RV9pB zT$~HgvRQrOI6ahRfcN5#X@GtmNVuT-0dxf(Z8IX6@DkDj@8f*q{I_oSYnb5ykQT*hUkRZIxe{A{LCJMY>Z5<=RS$I6DoPil1*p3I zEch7#_%Qo>lqjbF_X=!kpgL1XKH;~oR)|FYOiF1UKRfFc77K<03GhPF7y+#ILx6j8 zOw%(OMmWgHX~?;pRXc=p{}^Ig$`Jb9l_v(RC_|am|LyzSxYk)*e`0S)J zFy=z`LAWZK67dLZ^9p2PAvr^Tn!PT6YcvLoWd&l!rTuDnk81mbU2qr41OtsG>^>|c zw_(HNt|lm&fyCDNLmyAV5m`YZ>0~XL8AaRq>wa+HXuB9T&_gm-)6)wqypn%Ob|)Z& zOzRiMF%q0PrJV}3elGMTJ~0))8?SCNVW0Sdwi6;X~Z4c^adO`shx&z<7Zt`8oLP&t0d(o>`|x->vvNDo_+Y#T$&B zuCfA)Aw$Tg)B%^PityE23@X$OCh-S46ij8|`x@AzQ62&}{3WNAB*X}AKO2I0n-&r; z&<JWgn|KGkGLJeX#b3`|`kP6i5T&&o1angIwXvOC?nv>fU#x(`GdIVadjXhX zZF&|R{kzBz2>)|Eps8Lu>l=z{QP<7(0>;<1Sz7j3Fk#vSg%Hq_rgTvJb~wlcJKi#7 zKK>Gv2}kz=N$)yR;-q_Tb(x{wUKB;>#?g39Jh;wxPZ5H7+?kU*c`@8)$ED@pmcHI! zT18I(#=xPN5`qj?Z*QvBN%1I=f5TyEo|;S(t@6?md&5bICGm$PIOh)$X6jvPi!WKh zPL78Lg35F7e4tD}C^qTXi4u5n<&zwP(M}QMa0%0(8Zxb|h0hNeS%Ph#mQ;{bGLqEM z#Fa-#V+vvKsotxG#f|%L@u+A36neYa*{X0n0m_?$gBOo>f&|nnWh{}7+ zKrGLogkOb6?nBnedD9e!%X^z8`KN1_n(57nUH8q=pp4^Cl@u zTt|4rAq5=UhkJV?#Px&fX-o7i=u>4+wgd&&)(%2vt1FFk^yn3qW9(=Ek37eFXn+zw zL~Vb`jSI+9{jpkqQ)=RR-=mb35B|2SveY&v6NhLgAcpmU=;E^@CZ005u0H9%S>otM z+|+wWfvii+c*bJ_($ge3?M`}hR{QukA>qYVBx0c_kYkJUb!sALO2p7fqlFi;QpxPVO-Q5C@Wow{XV)= zVKGer^M82RO)+d|=hz)g7-ol%0ZN@AcmH6?cNXg0xQ1OgfgoNnI;~|zq~59=Y36y} z@Tt?E?w51|Kc~Rh<>i)lqMy$njHOgg#nR8-9rESdFz?5`s5aA!Jl~mb5Dwa5n*k_*CG}zK#o#u?;qE_bG6Ud-@8sgA_X94lY0t0Sz!c*d zF@X8|&p8{4jA{rUF~091t8eg>6gL5d8dI(1Qk1o;713+9mV}3@nm<8&OJL`lFgRxC zknX-Q7-(Xlri#4=Z&}3aEDZ6v_0G+pgiIugXfX`YAPWY;Eg){LWU_@h*&+{f0g4U5 zb5Zcry4n3to#CdXh(S*}-+$k_eB+M-$LFlkQbKYzr+Sur0sI4tw>Mk=j@Bn+U;@q0 zjZ3?LJf9}I$toSg{YMpAYd{q|+23DaXH^K>gHt$DE2(li_~I;9LA^0y2-;=}p9N(g z->H1!aD4aO^vZ$&DITDa5s;p9f+Pxp3TWzTZD{rJ;clq=;7=m(7EYF$*s)U#h>ZY@ z^1obO0N-sBl^o8^z`g2QE3U3TAYQ~fRlZakcGnuf>+Il7?1F~ujjrKFaDJr*tn)AfGa!^ zG7oUU7+y&^dIQpC{vRoWzW!qk%Uu4u;A%UhTeX&vJ`?!xuU;Y5K&485L<0c|AfJJQ z`*2`da+3Comxnh}^G$np0OXnX2Hg6^C30d{)6&oh0D>@F)0M*suqu+ZjqjV>6dUSfirp->m9)df?JO(CWz8sXT0VMFw-bSmGwu66w0}_I;6t zj08IqGr5DG()0_LX+11$+L8(mbM3-4jD@DTor~D~O7QLarXqEedgCJgzKfFFlmjf; zT;9ystUR0*n4Su{_;W=ahr5Xp<5%cypd-Tl@}~s5A*g!@vEP65PMo%XwS2ZpNOEoC zoEToz@+|JBmf7{I2!mMm8&)@;RrFh7&_O|9{1afK(WkM8%JB{vOOCMgGWP}#O z8_}TpjNd*s`1OW~3i((4U}9+0`eHLY={&?Ewk^x-c+2XUIqoxiqsx--yq{hvQ&s6! zJ^5C(r+1!}%2=huqDp|U1?=kp9y)p;y^N8}U{E94%v7U3SoR$(OL?hWQ}=_eF%X9j z_@D$bdRy7L6q~%HoNuAwEg=X0;U@4+8GsCd$CoA-+g`SnHO_1kCG=j`uK{17ey5!>TcMjBm?;|UYYwA~@d0i|Hsp#spp$>-kn33iy= zUX6BKnDSdpHq%5>$sndlF&GqXNL96#Ur=i##npw1Z$5BYq+xr;B}o)geD}=yI1{_^ zJ$S?87RDl&UnO)=PwQh)iuo0=Q2fUMfumSk0{W3jh8Yq0N$UM%%%! z3=P4lp6%W-;ZK~%0w)r4W49MHnSSY!(vvOEQO~%7f&W+b0zukz!V|Ua{KEMtpeHWhm*Cf9Xl~%CWdp z+0Wh~oz6mj;R6P^*lJAx1WW0lbjBZ}mqNip<2V%vOY?F@Eyaw~)38dFKF_K(fk;@FEW_Cw}B{ zvG0rVoMZ@@=v?Kr5~ReXE6mraiqEf=`dDp_LoQH-^k$XTJ-bg0j9$n? zv|{8nh3gL^Y+^^j6t#^3sNS2SEKFLFqH=t7rAF2oC*FFeA7PnH^P!N+5KMJa)0p6H z`u%S+%gy1!m&1kV;iTIR)IFx%Q69USMG7 zQ42$!k!xZZTLeLtyRCT9dyi|L7xpNWdQ*yTbxG zk&hqV@_j~6>ODk184Y1o&I0Gj<-xg3LRDvg7hgYo5zQDz4Of=gTXWd9+^J%Hq%PBn0z6?s?ph1&t1GF`2 zhfkWbs6zv$vYiO)ov=xWYD9(lXzh3y+hecYWSdUvsPrY|@$3ICBPxEfPyU;Q)b?A= zzW7pP@1xN~Rwb8htDEwF!yLmDwB(1wZdH46?urN;qeek#fbd%aF#Vi?*v&FQ_LT)3 z1%&qu*MzB!PKmY~&~)I5i>nd!QZGag4ExLMYVEjSuw^X1=0R+~m&9;-URv&+Gq?*F z0XZ@;J-N-?N z07S2usIJqf?4P9HOUvYDZ1EtukQ0Bz+=26iwByxEh z*YGdO)bsy?G9N%;(3mWwFi#-wwmU&K++y2fl_jY0g**oo@gB)ntxW5#%D_chGr1qM zH7sxqP=$;0z3>HST^iOwp&IY@Iu;jK81w-~LWQRM$J>*q?dN-2{j{4@_TWG0Xr975nPsIpUxs_u$MK4mmm0Vd(;~N)NlS zNnPG)B*mpV(Y(FOA3u=X2VG*BGN>D9Ht&xYrK zgDIm}?Lx2_(R+4(0KZ3n(u=$Z&|#wH=i)P#FMc>3W6zNgEwOSrCG`W{*tDaexgW20 z!dw@WZZF)qL4BH75Nyku1H|C?=(d03klvEt&*(Q{A?aNBKyNdR;AzEoF}tYzpl%$C zuyqkr6i$#ZjM6a#95?sIZ2e)ykFXdh6rq{xL$MpDOat+|QnytLit+_%Ap0@4TdN&B93t}HB-H^3a!TUdw7IKSdWL!NYoqY)Ke##GEoh8 z(=jA_>w3%)>IOk6wL8ZaG}iAOfu2;BCC#D0mTU?duqSLpaMYS6O3r3uu=Fll(s0}F zX)#3cWtC=DkRfDbsA=WjfQ@Sni=6w7*vdL!L@>p59&=-H~ z$G0o~Zvv&sMFLH`W@&vZq>5(W%?gK$Ud`XUpK(uctCzjXf@y{oAP;(s!A`LRKqA7V z9qRDt?H@kIem{9RTSrb7-arFZ2SPRW^BMM~s6Ihj6S4M< zM$HU~wk`wZ;_m|FNqan0-+1iXeu0}q^`lY8g;y3R5d)HdhB%m&A$Fc5J{PsoY_6gf zIE#?;GN6EJ)?)x?LyI(AiI!#*sah73U|t1i4s%rg8-)FB!@sYmC#G7wA^hbmKRhet zbvdYT>EH-l`-3)vLM^Mm!}dfpKHUSESQcOJ(wfX1`~ICKLKTa4Vcwptb3&naiWuo@ z=es@MUZvcPi^3xUtxTJ;{eBVwJ<{lFqcs8*PM)^t+DYXP)u2ab?}qJ*4wQZ=46R9V z(6es8bGMCB#R}G}1u%3 z2h`iZH`*s&(-TG~z~HgRc7{C2)Ly9Nisu!e6rBuqm;O$QIh`dn%6V~GtKpLE=EnRa zIM8K`*x6x^I&JGj+9?Zqs242R>Evl@vHnLE{`m>}IV}U>T3G%oQ?>x_6_kB~_DjD? zMlaJsu~AN8mXzTyA`!=yv0;VKLyL=ou|trIy(i+9v9t_)fMrC|+)V;5LfhyBFMfI! z0!EU0X_7g|LntVo19m$s4QT)kUOHkrZO8dnwXklew|608qcJZ?bB*u(Q#LT{`VS$w zo%PB<%00&SPd}#r&C{|l$xtI$+F+yuamK~{DbmLudA>G{{Kmd-mZj54X@c9)#IGz< z;)tC`4U7}z2GtEIZU<9fN9nrw$B=%CuI~5kG3{N;2GG{1EB2nfHc+G4n0|Fpg=QZ# zE=3)Zy~cf_DGId$-T`B7-f7o5>u3h+24`1Bw{iNAz$jLl z%?{bA&@3#^a!|mO6X>@DL{fWo<;l)mjc|2f7n!bS*=Gur_g|=@slbM_US)wIgA3w{ zhFTzY|I6E)Wa0LDWt&c(k6@lASHgyYi$7uevPcM|V^UcyZ8$nmT&TOoNMbkn$kUlOJlt>2d>=k?IFI|}9=cG2A!`jeG;^p#_u(3?O?`I9 zNBLx;>7I)|RI~ru-^U+~ zRb#D$)EV;oACbf2=^R&EwO-`pb)5kbz-I=XG3vvc9fJQa+Kz{UPUM;N6Q22$Ye15Wp1M4J%0yMihxQ6p_LDQ<| zgFC`7?o34lO||14EHTayHa@T`L37C3O+>F}?%!hdurFd5ib&La?E6&4xU1kM>QIx4 zQmlWoLb6#@^glAO&-1-_3a0AoeDXYA+kJWGLY(~LiewvyR3MI>|Hc7pC>#9w1po%c zB~(6pH54lAH8|`ulwcyTYm%XQ?_Q5jFzn@4s{7m;ud&i8<5tFf3y?L+LPen{TFfDx zaD+6hA<^N8Z$<05o0$=hbXAmL4AfK4ob<;=X}fkIEDsM)wRA89x+;d9sVw4%Co@uy zzlL3pV{RNyQsd~Bo*IlNI)V60~%&j#C7jJxHoK$Dwe}ovzH>&WO6Uq zKBU(nPqRpmcoc#@s7%f^g;0@93FlVS`|q%cY33*O1Zb|VdQcJ zMr|KKZW(LU$K`zhON9n1sKkkATO+izroM7O5eBK6{xdYu`51d8#~=Z_XECVS)TC|W zSB7U2jY&!21C7@L4gLHg8Oy`yqU?OC3KyKKGJpGpo$GE^a#MPn*@y)@-2Xcou8_B$ zqpQb6WhGy(|B@=ocCobOLH2h>FBq3!Y5LkANc3_(U?sN=q}^>lqj>KOL(OLI76SX$0yqbq?l_It@rv*i(i7Hq+z=(5|2VA1n34 zB4uC5PW)k|{&bohh7!9^oHbC@gn2}#k^?w(wxR;h&Q2wIK&yPjC70ME8I1*d6=G;1 zQ)F#fRt~gl9g8EaT{^`bM5p95=Jz32F9szKZqFP(0EC! zog4_$GJf70k5U!A+f5>ndRu?U8o+MU#3U*JDFcD8^$oD}p`a|G*0TpS}jP5X)>O(Zc)N;z{^;&k)8s~ALXKNzm1R}Qp(Q*q=y zanINLQ8@#^rD6VCl6`P{8N=*`%ReI|@i4k+tiLOa!(Lu44lZJS{tmJJ?5~)ijhstz zN_E#lYhuH<&*)&vUkS~xxX&Jthv)7{faI@ye5)*V^CFy`B}zEF6+H-THYiol2w#Va z*YcY%(O@x=@a1fyl4{_dV~8m1d|!jo;PX3g?;bXm{tnaUA~YDRss~!r>JgW+K92M|TnY03wj)11bS6PShaDlk z*YHMXXzt6Wzt8Z=U+SsAni-njAl~KR4}BIwKqmZOa`_9bo9}!j%wXv3A&Qd9<3NhA z4wW{S+zFHZY#?wrjE7R-$C4u!WC z_rk*+U>qY3=Zivd|9#vXfVOaBp3&5=3|yJX?c1Df^TCh|2VFEl-uf6jO2eZcY5)eL z;L!1A2~PN0Ds{WCfHX<&PAdc&X$Kw_h7e1O98Lje0JlRbKIjfvFRacxvE}Rj7opl< z{t8-T;DfKI(ZQMDfYdcGA*_W9@(NHN1<-g0#J~gXOj_=P))1DFaLhqBZ=g>b9c1er z3{OniVcto}*k1lAedjLI1d~_Os~JA2FqKw#pR}4dXebJmp#=hXnR;#3byg`>4c+|I z5P8)ePeki5<9h-OA!0x5Urr8MQlgmgJ0kgfsm;Pq_Ik%ftWU+g5|vPz21h#t?_CEC z71ZsRlg9SPFp*Jt-0NSJ!1Cls_=4IUXF*?);%|ZFNVJu}4Vd~_WVIYn>Xy`;wtyd# zDe8WmoDB^)AP8-&SrRhruVVI@KBcPs;pF+Qt>i33P_gPzBrC{)5;eU4I1TdH1`C72vSJ$71EWozLe$$#5k8dx2-gB*XF!TZO) z4Gr}fA0JoT>Xef^_{JMX9nVT`wPLq;{0~fBV}aYF2)oQ7FD^k1L%Hqsr_7Wv%?J%M z7~x>YZ2K4s4FG|*3eq*+fiq_jXjEs%f<+E=d*b0?9>{enAmfe_M8;k9ZK#U>Hy`?( z`Dw*}R2Ff&CgXqYM-l%BPeDVSu>~*E3+L6NLxhG~WgT>M&%9H;9UAld3l)rVZ@`Km z1=NBJzm&rVdk7z!;m6kAPp^%UA3fwWlnF@qDRGcPw&g9@s6|rJ{=U{O%pCa!e)kZ& znT(6tMwq6pfcn+sKzU6PK#7s+;^uz{QjUe5X#a&_-=D=$$w;K(s?sb4dfrbhatr3$ zw{Kr;2p6$q$48vMhl+nuOGwQ>g+Mj_l}UYfb`Qcd_c2s6S$!7F)BjFXK6GbIbo&*@ z$8I&ri2b@pbsrL2)FV_a{D?I}v?B1Ap8R#4CF&|vrNQ7in4pUax-V{yahHv*y@w8O zKA6VS|EcDk|BNg@!tgk&;sO8+JhgJL7=^Fk`Y4tJ5Z42Zoyh{;!$|y-VXgl z|2%>faS4q4pjo2-{5P1;0B^zE6)GzIXZLKFc%ezg{k&!e2yBD_>Q_7cm^)wO?D!Xu zp(zSJQT-ArJnFM>Z%@bY>TW6sG!*uWYpQNHaJ{A>FE2lF)KtuMz4api6-<($>0toY z!SeoKZ}jtnxTfFexZWCo=AnmL@8?lZ*6h!4!o!!sA|eXJ@%!94g^sM9K5+yS%Q)(K zZ7N4P_O$@c-`okf4c0s5-i?wR=J&y8a<@P^0OVGM?{!0UpQ53^lI=n!)l-SfLh%&%u+6kTu`IUfz5ch>*L?bB$dP zTm(#m!$mnF+jxS98niMC9Pg_;SUY1Ygzq?M8pK|)7J@%(HyyOi`-5`X7*d4)&)V!_ zXeCt5Mwj*=6=w-xeXt##B#p<^2}|n7`z6CPlLq)pT8OA%>NE%J{NGTp9_7EWUme;m#xgf*>orv1a2V?n|)Qu zA!U``#CTDzTm#)_i>2I^UJX?^(>$XRL-@Hf8szuQ&mdRyrC?vwy+y0#nf*x&=DJUy zMMwSpgeDG(3_?${gy z+*>)oqvH!poW1a1X}6s`@~u79zEto(>ERjPE?a$;EHpUjm)LGt5!o};+pV1XE-39g zEhLoTTBClX=$@tpWa(8d&5S^FFuWB91m`XTpm5&=F@dvyQFkP?n)K9Y>)K&hLj-EC zXxj5HFr$7-Ty=0E%vmzcGj$swlfHtqb;skjVY?kB?{{R88^(uOzc0bcQ0 zA$v(i9RN{|JF#OTiXA@JCMf<}Kq7kRX@V75gGD~Q6T!`~mlG}h; zZp|6%A)qjipsSEM#RBKcd|Vtr6Z%YYd}S1{#{JmVDu9&li4Bp!QY{wZ^JLxSQD7VR;Tl( z-qKgLF_rQgr;6ugae9&P)+-Ok1uA<#jg|Xz-S`+06WtbAmFch4C6W%^cIx6VeP*fe zj+V(qIP zLM^yGd*O2|+*@V#^WK2;%uX|=rX<2SW~^mN)c-=-W9aj6*Bwu+xRjS86161GcLgBmPeZ@z(visD<< zQso&>`b&N_hKmW39D~*ZlA3g*5_d2^|Nj<*L?$pZkMoZc$aHJ?i^gdcPoLB^zf`t% zl~qdH;})*=Wmz@_SOz4=QGnnc4v>o6AQX8~tE+o^>~rb-Giq1zI-hwio`c`lIfm4F zr>C43bDVB}09yLIg?g&DPT%GM(>*m0TSgo5?r)hku65s37YJ{J@sxrwB&zoyBWNZ! z9D6dm3pqF}hhCiqZX7cob3NBImm9jd_bn%m4mZ6Gp0=qCGnk)}dY$!tK=(q6O55{& z>AL?}RWL%&>gYd_*3NDp)SI%*x1{Bt!5_4p0^tqGi>C28U)nAG1od7X1V92mf?6-# zU7&FSL;r6@Y7CD~uYS`gNuQ#n!1aFc=5WNRzsIM&1orVk~VDsWq0i(MVKuuwTgau@IPmB ztpB)L=v5jjN+&G{xjw!GS>7AR*&lKuZ?zY>THBAnq7PA{OB(E8>bEYI4o|dFzi=F$ zGzj1)jDK+$4oa)yFd&>LnXl%cHJGg6cl^6(LM`o?M)7*ve5Fw7slMN%LK^4pn26d8 z-eQ)tJ@KrM`_QNrF4K@wRiZx;85!PGjjkz$aa`!B^7aN+ zMZ+ig6S}n$pr|VBGOQ3TY_lL@AO%yU`JD#Hhnx)-9;3%vDr< z&0n*67J2H&QHkPWn+jTuRzZ2e`ntOE7OxVfmX?;rjlSVw)jIf#l@d)*e^J>W7-wAm zV=*ck~FHF9ZxtTVOTvsEOdx?tb2(AOyjVWKki%u;URk`fOHQ|nn$zFd^7S6R49 zHh(^uA0cIX-k-mjI~YlS|9K?wHSxT?3eEL*qAdNcqoHOR0=mD<^sUucKfc|~tJlze zaYvb4fGUITVvHFvMfcmbo2&Dyzh()-ZtGS3hf5cGN_!8PKCQSOE=*0>HY*%Vv0C%V zThyC<_Jks2R)&&I@~{${=!0g|>X6V9H}Q%rY6cvi=6fW>UMv{E5WwXWaz0@DxVIH? zGo@14>TFwcUg-D|hIGHj%@S3MmiVNo*|xT*s^*8PRH{VMz!FF!9nSmno$CjA`O%P^ zxBwoWVTZ%-APW%e$%8JP924IH{^sn>H=fAhD9}ZOlild1P%tXh zE27TZKsLm8kqY4)@pC`F$EFrdmxFQzAJFkDx@>qZ*p13tn=(~7`>w0+n znwCbgj{TQ_W!h{5#kpoGg7Az>N8v=~*MZKAA)7fLl$e1jY$U@!;KdX_IhLe@qoCAu zBf|w!0W9)1mv8o};a&|i*cbCix)S3O-Fp4~{qx^{37&+(^YXejBLyd=mRrBQJSQPY zTgAya2ze4={K74@EZ6mIr3wTp+lF%iLvZalej=M=R9(PjCDd%NHK9eV^rG}j#%JC- zH@!69%g9YBgrmX%;v?qPpn7nzrVY1Ux zT2D%Y`;c8-UBdA5NjAUd283-_LlbXpRdNKB6LYrclk~5=iHPu@m9!HE5hgvn=6+iU zlm_Kwsi_sM(qgmtFo^t81D>Z+14S%|DGdKDSWDKw_?W)jLdd=X{UJBld|?_)-4It? zEP*mZ-q+IH@b}z?!UkjcogLNM#du*RZ+6K*xz9_aPdpquAualW@ z*azEAa}>>0@cYzTxv1Rx@w-M7vP^0U5AP(2iVi}>QLAWxupZr+Hy&JjhEp}^)m$%B z-ex5iuRk>HQPPb8>0CHQEFlzMkVfb6P=1D@2eUB!oF}tJg4EheuihabW#}q(OD&kMlcJt zzJoY8MKbapYn=m(z=G3HAmkP+-RgP0na{R9z~;{LoN= zSy)*Gye^tDo$s#Kt9|=@4xyV^|59outKCHFxbSNEOLYO9Y9rFR2PUY3h64CJVeDlf zZZ!0P@qU_*&pWnT~qvMXoxyteUX-Zpy%0EVLZ9w8cIFTm9h zsJIxQq|KMe{Dm5xp+>1SpH=(aW*YQGlMP~n8wQJS9mZ?*S;O?VCd{p@(&T@bI)1Cw zr%Q9|okT-wpRp3fh~v3~L1~1o$Nl_tzDNryGKQ*n{K!7<1?D*Ax0(FMX3;DYoVhYW zSR=jN(k+13L^qeAAo(+^TRdq+=O4N*(9BD1HBm{7O={@cTyhzVAToya&v|OgCnxfx z>e8pVO;5g$d7OP1Y}^~fI(G%9+Bc%vGs=N9Sa{!W_E!yHFr{U13qE&t}12 zm^@YG2KyU~DJ2e!xlI3R_HkH9h)XfY#TP?B!rNScYGf!Cw=;`p2wlgLLxvC4HEYgg9V7BmMrs(qK&cSub6NqK=RF(t z@Dsxf64gHy+yPD0C|Tc#fkVn<+n6!f$VTc1V-v<1Pwf85j(IyQXSB0-6KJ5?5fpV* z09$|_VLc93$9L$_&lW8DXQn!CEfIO$W~QYIf0*NQ6Jt2GiPOE#f$v6)#@6Irudj^z zYV)1QKl$XZkb|R~&AsQ3>ehA}KL3`=GE^S@>Sw5r&AqA!zg)v=^{Dn+FKllv+#2k( zNxXgWoBz<&$F-_=E$XjkCS096$sk^NE{g83rrc4I1G}<3bR=iJ(qdW9D(&Vc?S)W6 zdC1@zWU!k3B8A-)gV{16orW4lsJa;$NCPHNN3dZIOffv_!Ru-V(x-`_vyDzy+4 zN#RAswx6)FLg;V8(+mw6-MxGMRa~vnUE2k`6hHp8j7Gu{^%O?3VprE|#m$Bn;on9r z9`qhtO4Am<3Zz!Qzy8YRwv==u7k9SMiZG@VGh4Kf7^B6f6XsN_D=I1~$tJTp-YN#g z1Bt(YGBw;|V$5G2UiGn4nSB!wyp`l)N^7`}l#2DB0ddjUY;(psUZzEzRp;^F~~*&>eL%gfut9UnQl%K9Xnzi!7ZdtAvc`f2v`kW7f_ zz|Tj!jT%#%J^SvReJK-t=%Rtc4cQLyECQi3%X#H-B*o{==^uhl2GPpTRbu!ulhrq_ zPC%BdDB>76H2E9~KV6*^b?2LKPR1FF{5P#|)k(818$AQ92`U%1HwmRf%jS*Rx%c%} zmz*W(ot&M^qUk9;tL*(eeO?YV&k(N!+lq*1+go)KTTAwq@)<3?6^terMnzkcEPmci z?!<}nn>>x5{=3*nGBLPDOvMUv#!Gtu$3$+XnXxItUo&@rPNfmMA{$q;nEHv^+*a}q zv3^YaWTh~u@{+@S;&%MXyKg}m8R;wY66F4e8^nm4o|43OR<1k{xt#eGiWB&#=5HCV zo+Q!Zc{%l3F-$hmpg}RWLbmpn^aRCXb8kzQ(9%BlB2kAq!__LT$ng2G+^z3b^dtGR zZjFUyvo7=Y^do&%x9-~7ez_q-Onl_o|6=aRETMFKjHD?qL^S7kQg5ge5cD)o6qNc{ zmT@rEwzM!Ip~+;dh9wB$hTH5*m!=sA%OSZ%Fph2_iGI3EY9lD%X~5=>M!xPX1D?yT znttgV-X4hddh14qtH1NkgekEDQ_CbwCEiDvu6*b_%jO}Ikz?2K%Qe9s7A52pw_(vN z#Y5zqh5cJAimWH6dU`f}?bbCYp7xcLIKq#}P~a4kkq}gCl5!~m?p;MfAna^b zJLRDs62j?z|6K}3#>U3&LyVHPwcnrairmO8Wj#|om3h)po$UD4aAvATHiy*l$qow2 zi@(<-3hjlqcyWv!SE??4y7G$x*K`Iuw;QKk3&p`cQx>MV-H)(t4^WwHcE!HdqiYbG zEjroN+~3bu;?^(pRi|$uPrZ>tnBKM?R+N3FVbUHxkQMO8Z;wpuall>9@AK zOS?gOxVc7b?XyLAbNOO@gCM6WT}&_JZ|^^R--WpG+WMQ~jjx2wA*lmN>M7cpW;6Y{ zX$g}DJY;^c9eqQzi*PGQ7=vW9`u>;bV3?s*Bap446^@K7T0N=n1(@2Wn%wuen~t`# zbyb2t99q8b+kgD2^?2-SPv_Z<%d6wW5yIBDv?Z#8Pw`fa2gj22m=1V+O_C%Gc4k;_ zb~anzx|f_Vb`4~t^73VLZd%%aMWa?0=hf!{jgwi8Q~hk5TwJmSG>s%tB4YM_efIM` zXVw>alSZ~zUQKFkwH$w1s4|NX2pRtu8wy-)83&crre|r%-L^!ui!(6gP}gZZcEG-5 zwJ=)sw1;BOz5U<_P9`%kyXZYXBtw?ek-R_bOcD3N;-MPPKFzr+Ui!kFt@y1ZM(2oJ zm>64}db1-Jp^f_f5)xeZBV^uiC1qgR-vVdusx;FpHq;ohp6A)I-WA|-VzbhUxLibR zDos*d|2wZKp2NiCcv2f9)I4)fi*vx#XWMu0^h$$~+^)>Q*;AtP@o7tJD}+Z-RSDwi z?t>~-M(R0rnJVTD`}Ho^vF)FATq$HKxDAd&koF|A)WhTf3mGzs;$S0N+sp(rI39WX zX_xe@ti=ZtEOrSUlRTcel+y~Jt2pE|Y=do06+u%6^7grRZ4LEtfnK%E7Tn(dx^Ai^ za$7ZTDznnxKhLmbRQYr;W5MmgVF%ersidH>DaWadj}auFzXF;PUc#1z5m#qJJKpbi zkix1lQ~TVKf4*=kiQ)aMlH&v4E7{#E9*mXdbKLupXVVwSf8@Zxk41j-UkqGTVHAf8 z!U`xM9OFJx`UcigGo#FM(8W3fxI;lGr1F{yS%G0`^&*scm!1+`)MQBEISCC>mAHzUgT8 z=cV%{Hp|#b2GR^3f=r8U-G{U-d8u3D7~`|U;G1E4D%bYx2G6{>J#}GYMaYGK8#E6E z6hUVKJk&m)AaNG=**4qKe7O5=cK6F2BT7H3Bt9>tE+hBLELoIBYqSrK2((0fq`7SDdWcCR%AI#{F4B3DemBjCYNa8eM!^+A*kN8=7b*5h`FTMw7 zZlD+Yy${pq|sCocVszGTkv z744IINO78}m?E`iO+^4{Cq2jgA~#O8!E> z*HUL@%p3O|Be3>nFMergXlO~WuZz`ASw^hr;u7f6!;?stqO?=ojxBkvS?lipys78% z?Iav*YwInQM(!hwVvh5`fUZf5WuG3geRI@`R{{E6DWuGdH;0R)oYzA5DEisl^9ruS zmLk`hnfwrx2wvq1yjFU74!8hbB_%5bI5M#Q>d5U!Y80;9P2{98;w#minzE6z27-r1 z@*ypq#N4Bt)Ry{pF+@^&$Pa~RN+c0PVOPIq#@$YU*Hm8^U2J%_V#eg!^I0p2ar4PG zyzXB4{eXi5Yr7i-A6(;*S1elAS`^H4b5&`?9g9#G$%z)1C^kZ3MVzoZ2u{t=r|oW= z4#Fpy=+z{^{7*0J8s8BD4}DdvIwp`vFg$kTfQM(QBlvsI?I>b!CNKF$WOv6LesUja zm{VWtaDpR29cJZGrP$t+m8hM;cFeM~<5=CkaHld|putK~1r}pZz;%9l;me=@A-YkB zX@5BM?3Q&*xwGyCQEy zRM{AHxgh(8n#~S5zkSB})>TX=;eOj))nTyf z6XFYVWsB=m<=;jhKiz)xsHyaBRKjGyb3YFN>49)T3t8glM2+HaQQ~@(G+b3>^Cnfm zKn1f?l)0Z$Slyrc^(>2#Lg1pK>@Mm12oY6M)TP1!3lP{I?Jb_1!Op}7oymSRo;JS( zp}Gpt>iWWk#H3M{6G%K)@|i)kJR|M;*2cVw1BB=Wo*qJw0MC*SD{@~nPK zz07CdvTli~BAmOSO%byIK^TCxh}oMQX;L5ulrlrAtDEMQ!4pc7;dOUQFZS8A1yi_| zba6)kOB|1(rc=~NX#L$o4dhnV(Ld&d{+(J{4S^+Q9GyJU%~P+7^+`c_u!B}e(JtoM zF&OE^)S`*RblZ^{pg^F~EsX^~Q^MXl6@E4Dav8XEt&}CYnaF&mzaSfULArxzVL?eK zsK~_9`m=!)S+SeojLo?oLo9mo<|z$ZqT3xXecm6z8hV1Wjn_c}J}>K8ij}$P$}YXu z?QYG^&`ZCg0#w6%eVxN=jP1nlUtI&@opXW=x(1N>)P za$0-0jFFmoC^O>>MW}(t@;*X{^#|`f3b%{>NcV$p86QhwV!lduvfN?$3z*^WHT#lD zJ#r^joNpX>*fg*-#gMjV9I|CShi^tb76)!C=((V-a+!wXEPZt|X4gXsC zmdPu=QnwA}KfBSF8)ddDJr7a1&lc#|>9qdyGlv@Ch-mv!C!~~ej>}!vKYuJXQh^J3Jfp^ar3Qr7jeExfFkC>*32+l8GDE3oPi*};46-J zI9nUA0~fY}wNVsiK>YZ%b@I|F9K9o6UvN z?W?PPje^U$kK>lNxzTAXReRXACsT|iYcYX)PHID2i8syGsGy3yX%8MJI;l`h+hy)@ zL=W)+_v=~;y`gC`XgEU(R@2f_`pT*5USiwb#+>LNi{ew1fB}FyFs>p|Jqhp=Q!`ER z`l6H3x@Wvxoe7^5eD$5|WWX~Eo7H!tx7{2z0DK2P`~1F=3<&K}h_MA--sN&Y_YiU; z`i+ty5O{sI@dvJaCxr+}^HMKEkFrs1MBd%hd?GG({vusOPig7EWKO?R z5?bR8T7!0%EzVsXTi`^Qj@LsJWP$!`>Own*THeh1BvZ*ub!TU$&*8UQD+?dLe3|a-p$sh;EkDsm*EyHM!0yf6wH#Y-#%z#Cn34QTAMk?;H@vJ%Hiauy>1nD9Z-M-bsT z)V1ScXd&68$m623-%vz!<%eAv8}XY)nEzp5hN~GdMjaefUdW(z+lx>Fr;624Se)=P ze{b)Y#{E(WUDtZSAa#;J(iH1^va!1AU*RX452L8$R`%VcRKSLt6Ekk}&CTx`K?j;r z&y)a^hbvpl>OC)B4v*6r2EKBO;YLsd%}zzd5KcKE+z0F z`iHPOIzMGC!=qi5^A+me$WyLvm(kkz`%d)@N`#u_Xm+`5o&7_6jzxiYP z&V{Ly)xyND8#9C~0Knis`8I^EpYCRB9~E;sp?W$PLfTo^{*A96>%+<}V^F_)4<6 zZ{}pS+sJYcOAD@P-}P%(H}A^JS5-}dyKmLG{lYYR5UI$!!ppOY#e4twRXNrFoS}l* z-H8Xnw!h8eJ0{cCm#&2gc{R>lLPn%?kN_m0g?<9FG78F>WI#V0PJ zi(p(E`&vT6b^UkGO{>srKupPwlY!G>pHPrMv$Z=x=$6^qkO0G|xB`?}=g&S|otrd% znsw2#k6DuF!T;1=->&{JzmB$5@268PZdH`$c1eewq7x&s1HP!%jPM|?sCge#lGe$t zDsb({#fIn?>r?TwiXORMH$<`56%H)5(e(`4obF>&#o2YH`(%;Cuk=X3DoXI%Nq#eZ zczcjaXsg(5;DpY|V~07B0=N!VgDEK_woQ=!vvm9K-w)uNZdK;8*9|`r>PJip-|TO# zc^4^0mi-UvRQ*va0?zQEUhK`800?Zm-yMHSikODxnWEzmq&@zhBpJ5bhHo!v1}bDt zD5}WJEW3+DHv8B%|5{z;l45`$iakw76azbyWj5Y}(;n&c48vagI(lvDKhYObq1YQ~ z9c7&ZWdoh_LpNqt0IMkpt8HnXNE>UmLTW~Ia-QR&KVf_xk&>72acB%F)XqjG{vYy1%9IS7AV!P z_mU>oTkDZe_xG>0=YAy=6SqOj^Wz)C(=Zd78x1SN4oOR3D6Tev3-_t$wZEmXtHuON z)*X+ZU_xq0rRdE6L;Wt4%$RSTT(X{8ori?~cMp;$lO0}Y-{AW!R=>znc@S2&S6&tg z4y1%#^q}fuj^Ni7+DJJ%&PLxzR^t0n;+kTUc#Tb>Qr zP8On|^yJgY^{j<zv)>`F&wOpzSMAxVxSLbB`3R5GoQ^SLo%%zQuBJ$km+_aAtEnd|lPL$B_+?(6zo zpX2-ex$hgV0!2q(-`O|(&uu+Z-KEuUXr@l1&9uBwJ}*Fi${UJcnpgkpy#LI6n(PE8 z^2p*oq+jo;ho8C;az@3h7@D`pD=MEfud365lO4gdX${gQF-@PE$+3Wt4mVLa|95Re z?&?W7=V<8#d8!;E(x|`gUafpp&h<11-{`#Ik1ZY=qGO|b-rGBm9v=Rd=<6Gqlar%K z3esmwg}KnyL#`J&3Fow)m?{U2gRenu8jo0-8=$Bd8xX>&=Tr70I{&JJ&_wF~PlK*dA0Q?XW8AK6$zEj`Xa;e>0S54!O}ABxF~q)YfgKKS%`rB7()D zXp*?8uu-)uU^h-*aWMKJ2;t4CP)=MN7B3hY9Msh=31oJINu_?iZN)v>=5_G#u^l~B zijmBt^oHM0w5$TYsj8&#ys4;S(BkC@C5PpC`h_p^#nsn70K)$+C~nG1#01cR5dh#t zdE$f4GMiQADh)kd3l45`B?&4jRWCL;5ciwnyYfObi9}+Aft9?dg#Hs1_U15`jNO2v zLzV*5B%)03Uc5^o@D?bu=n_4>o!h^TFU9*$kh=qw&Kz+Xo$Ns-Xy#x>p`R?(L7D*v zI@jvR^}QKLlDc|ie0kpcK7-W8Cw47>(&PR@%*2m00sZ3v`QM~FpUL<4X?%zWFN99h z$$j|q_w+3{I_dU!q{oU8lWB~(5%0k{|C*;%tS(7N-gwN$hY?59m8)Z;Yfb2clOJ9B%)t3)IY(&lYaFAa;jQpvyfofrH_kE} zON4eYUAOfc{49cdh0;Ld@L^k$)v!3!p=H&3;->+I8_P`%x=4@(Y z-ftx(B~?-E@Z77Ca{gzn-n)Lzxkfe$>raI;)&`C<;~Q2cWjzw-regp{#FMMh-Zcy4 z<#lBYd67n|0x5=*369W#DK0C^n|f|fmy;32cS=NIX2w1HeBnlgq``qfRVmY^;ld*m zEAx`1^z;}o&#AB27yZ@5a}e!mggQYU5(QDN_xXy`8#l%U6ikITMdho=i>(99D#vL4 zz+5kbOS+S^Ga8g~^43hFc$UbDh?Sma`(Ibw<^?(~wuVmd`vY%8G==n^cjEluoM_{4 zU6N$R(5l>(kGPpg6D{U|GJq$TS8+4LU>v&`6qMWDuHA1hu+yDxUq{o|;$=EA_%F<> zmfsj%xrc9cB8pRf=2sbgSA}f54tdMud#lp{_DHjinez8ZwNZnIjwpHV$3s=6W1W0T zHuEkpS(9uLp1CeDC}IDxnMAYpVk96_dDs7xeVK7?3V=8u>Ki z$T@$0VZkKhXfM@VZlHz~8Tl{=kl|x(n zob3>(b71bM*0Rd?(;*(F0c3Lc8K{&twf#V@nIRDFyU`~_i^dK+1WpLvnj^gZU8|rlW>@bKGneG-a-8<<(=I&)jyrtW}YR#4(el!pY!$~lJIk^kreN<`0$QR3tbFw@ItEx^Pn`f@ODV&&RQa1<$Q#JSj z+KW@KM=r7<7Hwn=Laqw335QU)fspqC1$h zf@gu_9DmgnNlEKpd=urKR-%RZMnxoGQ$kj-G6)!wCO4Jb-@d1)-zuq&YIs&Y&7RBa zgUPDkACVQlBc}e_Z%J;&sU3z5eaqF*jUh&9M!Tm?L*oE)D=FP&o0V2aujK(SN}w|K zu677AQ)Nq}CYjwIQkAOCyrdzD-`Pc)wU8|}5oN|m;-qtw5Jx=$Z5og!WW(3FF&4fU zBWn_RRd~P&71#zh-m@|+oB5ru2R0yuY#`8Hv}X@gN(m4yM8PSb`Ij=A>5wps2t{hX|dOnMSZa=5-O%2d=#Trncsdfd<;B*@go$GQ4$ zc4xBpCiO>8hm%}O$Yd)b{gm&=e#d>1CNkyduJ=8pjPb>Do*Rw}G(X*z z9e`3goxfzA*{B*;6Lb$4Q&9Y4RiZ$R0a;jXA`Q>l+B~-Q8wvzx{fLldp8$B*(xt`% zDhBB-M0k-J=YavVBydC3XcAO)^d*9^{4L%t;8x-w0s;CrIhd0yK_ZbTaKbulwNe#i z3T59z=23Qe$=3*`+<1d3+FE*3}_nRDU+L!UxeafJ)GxDpayWpdfTP0Is(_H zBS7H3-gh?yam2I(Xi|+h5=?-I?fH9mX5w(Iz*gXazV1G-$+GA%_{<5aWE`;M576m< z=6}7AFP`WVa0wyG0oy>R{*eNJxd6~o2o=|n|Ao$go;R=+CQ72pOwvxh1!5m15)kyV z%H#oLE2JU=Q}9A*zQ!f=OXHA!{+p;Ek#QVuJ9ckE(-W!{>;#+&;Ptlu&(Z^sNA|Z( zI|V>0<}g6;egQ_$XaqVd5jz<)iHYbp2__~X+!yQ`hoo<=u_cshf1N~uU#9~EB*oKo zD-)rJ@faSz7BaI^(uq27dD7hcN?66U22#4_*`)&Cg2h+_!Q{11%Uxh% za02wSEXS^x4mnl*u#{wY2doH`u+QLqW8fUDkCj*UNP`^+V0#{kr2Ugl+w)Ec%1S)tJQ^C{cBAusZk)puCqBel$ zTEtVKXae0e2U(0USZaLh!-slQ6vOX;rGCXLt&tXZ{?OoV1Z@feEzm4oLTr_Rt*gN_ z66BPM^ywWzpe~0nbZ26(f7%6>mUjW2z4cBnOQcpxXnnW- ziHxwlnFP)me9q>8Iu%4I{cMILkS3^Qv@y-Ce#4i5*%>07zwt9SwVSR8^XCu)HTuaGp-nWDfx9xaW{1BZ~`rR^VK7 zb*dfjkX2eb@Ef*WY2~6ioorE!R0{0(3bvF0?zvy`3;aXT&v5jexpg|23;kx6nfw-w zbk?L@@uIW@XlHDFSH5__YS4jOn8bb!m=~v6`*C6sjfPluK!+8)Uih(=t%UA+Oa-i6 zU71X4FWm+&OK_+!X9fowT}uPWAxUI&QAMZ&lj={xTJmnfw{I?CQrxyPq|2-W1b_5` zs?^m&mC&+W?S3T7{&QW;uL@P_thk(Zy%LzBY{1;=6fzs*9l(;|p3*5S)&~m)ZNLh( zya9TL^#Zhe9UO!Lx9#|j?sy+iI(MXWo)|E9;>6JY%mF{&M9XXAA*1UuD6q%8Bwyb| z!_JnL-$&QKfG1cuM*B);-X3d$A`P?G&XT~usH5B!#}TSGPN7g8h6f;=JdMTrY>ILx zvbIyYJC5(mKi@P?Jvilo3)4r0qURXGv1i#FewDRRQIS_aBap~!6uCWL3@aTwOXQrP z4i1gU+P`*1F=TvvY@@?#S9t3)3N>zlsJ*G^34?E>-Z4X%_t92h@cIq zqN8m0;u{s|ULGvsPmd9o+Y|Z*yLXq_a3)4a^}E}ceiWUhb{U_S=lz2-uY-=bF%LM#e@KjIjHPwt>#cf;m*K zMx7Rax)*9#Q7OFB5YV8R5;Cr|@m9{&XjTQOcnkPTa-z*>vF%GSVP(TCZEa4fle%dC&P9Zqnjq8!VcLun)(&6>LLmr+An=AlO%Q5= pP!oj65>5!Off)#e@V^uSFEm`A6CCl&Rx0vH2hA+^=a`(n@_! literal 0 HcmV?d00001 diff --git a/src/qt/tello_png/left.png b/src/qt/tello_png/left.png new file mode 100644 index 0000000000000000000000000000000000000000..c3275604d6ac49238748bec9c6cc8036920c0b53 GIT binary patch literal 18119 zcmaf5^;?te+o!ukq#KbCq`MIiNAE%D76EBScPr95x?><9qq|#j^rTA|CEfYne*b}Y z$Fac=vfbCc>pIU*oknSEz9A-{B|t+%BYvx@1O|R?1J6A?9N^VTW_}j(g$@fH*DhDGauWp>GG5-G5-T^eKn$2$Tikp zck)B33y;rJUW5AY$LjA+cq=;Ek_M?#gw8+G$Me3K_%zj}n#q}1Ag)>XtJ-=ZUjsbd zkNx~hz#C^T8B{Bi)5;4~HLM>8Dq_L6WuMR~g4=Op0}mi$HFr#cZWiuxtgNiG80eYy z0a-aReizfeyf0W;*FnGPI_^9)e{rvnKY5}f_P$0IUTB;Wp`@gAC%8LrHY>qOO8aD@ zc3g#z8Ti-tQAEP5`BDGhtNSx*tK8ZFKh3pE_xP!)Rd%a4hu3?SMA;VC_msi~!ErXWcWw_#Su|uIrLu4$^ zjggordMJ6q2_04EvwrRf?+&#ULNu5qmuY)snVsR=Dd9I$wd7Xn+8||VMziPPy4gyg z!Emz3!`o))H$Gn8b8^L8Xejt=lAIe?SP-C9VwyyZi&yZEJj?FlHsH5<;coI77#B^k|!&NoxOC+(Ro7Sk9L%6_lrkSJmUO z)VSB|iZ~@goUX@h^g0YXO%UI^4s8?kP#m?c_CJjtSpBWJDN?#GOh)sm{0ou$v&MeR zL+^9X@_iX2L!;GOS%=|BGK@?Je?MCIve+Ve>FaQ^Q~{xt*;&zS&Ehw{e%04FcObn= z$iR5-ZGhw1q_?lH?~UHqKFj&4EDEdX8Fxp0vCxb}$2nj{h0w0oUxwPE6OQDb%#hJ+ zb7MKTcFJ?T%qbr-QbDUMXXS+P6On*CuG&eFRk_gScrdrRP(2g`+nU@tQw<7wvK%(Y(HpzslfS}-ZS+8$Lq?lJnrwoTrNEMiu|$1* z2st8xIdR{iVY4WicS4udxSsv}`&Vtw;o`63Lj9=8ZJHRR-^D%+IzI+lO-+qMU|`^- z8+`n)kLjYvQtDBkj@eaLvRL(S`oF6tQ_Ovj^|=sArWgt)fV*mU%Z*V#jZ(6F^?lGm zobOs;@Pi=h_rXkT7fQUb>ged`4lsApd<2;~*ZJbms!lI1o8b66Jj6Q!f^al2w>F5h zZ@mikK~Ms@@LgtUX69YA`B>x&@nIa)T-4ysH1POLMM;S>Y{uxcIw>k_)GZ%oylIUn z-k~jo9vPEHeZYv@kiW`z>nF@9g-rG&HoVp=W=DHE?7c z{vBk*baD9b;klHQ)Ggic@UVd*o;a$f{SXsPSR)KA3{23@$6Z1{7WT*yj@36Chx483 zZc5JiMn*Lux-bFUec3v6o#+|~t_s&538#rx;PRN$w@WZ|;h}T<>-bnyR<<`XmbI`V zwoX$eIS|j(0Riq~g20wge_S)1P!G$-Ph(>>6IVeLiAhGyuXC8eu}mOc%}%6yg%M8X z5{ui^>gI}uYWNkQfZtYEXdb*hHZu`wrHG&oI9 z_hncCW`TK^J=50L247i^Q@S4()GiKm?R=dQgt4SxtRU~9Py(j@&`-=rS5h4nWndFU zwfTAGI3AsdiEwCTOY_UfG^Dt0ktxPSMjDnZe*JxiQ(9Q6+tjKTI7UU{zJwO+htI;A zF`C_GcNps|=00H*vmqzviu%+0N497D^dpZbJ)=-JYa;K+mYDX+X;`Qib=z5(XyYIxBxFO%>mbH0jV|GT_rds83VXOTO7c}W8BiR8na7yJIjR2sm*CcO zH3XfBd5s~l~L7OiSi+94=%DFcPDN~b)DXU5(kGKrelX9FLT>bJ^aLEimQ@Nef;<= zOkNBe?GV%jljBNzK=Z_2%nt_Vw)+G4M0A0dpo$5ZU@JJE9cpxJOcl4$%^!uK8QLQ7bXU_JtqYLu2t3V^@{sllgGvFbLHuHrpK#+4wLFkPxcvp7YQW}}w&erpaB`#D{$)j=^>MM?j6gRAt_siOO+0uU9{FE)tMiyY64 zcl+hSFcjcZRe!^xKDg~PJpOgQUs0*xu)J^ddDJK#;3xv8yfV2FyEc{`7MCKY{aB?P z?&Pp9y&EZ~Y~Ku=RChCHvy~mQroA3M5nq`nds=4BUJvm2#cQyZGr|rw-3GJ7M@vv= zr)#a=weuwfHND??rrxjdI~jY0YMht>G~^d?xZW8OAO{o^E)n1IC$ZL#?Q~kj-;Q?@ z6BAo_%g*Ry`?%|Vcau&EW}~p@yST+`L~m*8c8I4>{rOe$AaR>8>)N`8u2bp8I6uxr z{?m>N`wmL%P*!e-g?h(0fs3K5t1IUb1fnBTwZ5~8;rTaw9^O|hiR$to{7|L*rr{nYUC$22gY=UE7>?fwC{%gL! zSctEyuhUfJI>bg>xlB}Nw@BhiAO`o2pOxu?x=veHM@n2O+uA(N#DY%6I##wllpTly zH{qlmK!+;&Uh-$)=QnH?toiu`j6BzlYr^656?quJ$1prspcY@8jf$=KH&57q{jI;~ zGvHXk4I7`Iy%AWb*5RR;n3$_#*>%rYmd9rw7Y=lmToR~uUTIg|VP3~Prt5epd;GEI z`&R7CkH+Q~FN#d7m#*#SJK&Z)%MLO#GehhcIW@6=DvkT`HQxU!j>*H_-T0d#V?MOI zD#HvHzNTYbwBs`L_qFSP6%?%*0#D=q((mt#X3w>F9VU|>rl+OH1#P}G^RbeFD?=@t z;VFgCR&DM&cJinu#k>T~7vCXq8@2rX^jz#yL~Vb>HKo4~#yrgB+|N1x9GKtj`s^g* za#x2mjn>l8$g8P&3j0=L>0cOHg!?xdz7Z-ge>5jZET-Kc9VC?W1*kQ>PhG|9i5IF# zJ=|;Kn8aPo)qKVhAt*n&<0!2dEe%Z;%IGfFJ-?I&0_;K|8g(tLg5qM_2ryT2$+ zy(8`hFQ;;zu9CAeU;D#(#fljcyBt%>bN>q8YQINFNT@}4)Z35?drZQ3AY!la89LCv^dpZ{5Gg0zt`J}h4C@AHIHa8eMC z`vg2H1q9qvw+VlJXqSzNjejjfq-v6{&B^?IkU0ktMjpDnY$|>6+e*wSQe58P{pRnN z6|LX6DR`*UageUVGB8>C1%*;}Y@`QW+jM`9LKL}qrd}bpxXooVoZ)fC?0$y#9gDD_ z;J5oQzCgRX?g+vo8B#|_N7dAi$~3vA@qO3W+s$#tvhi^Et6q(#MHWB_t_)BiBZ&xEqTfLgw-}hh`?4HBre2j2NLm5Qz_yJI#LMWMd+^i`$v1 z&nISQaf)@jYY?(6L60G$FV!T)$Hf}#FX2oqWUp}1{y?sa-gXHu%G01YYi+{k9HSLNz53AnsHS*jXLm|wrF@&3I?e?IH&Z%(? z26Qc6fjdgHSH_JA_jf3{psmHZn$`43Sf4T{OTy?!9quG^DN*vln@gc0Fz=BxRn>{R z*qZP5{(kRwEg7GUSffty*G>|ZkA)W066`a17jd3Id3*OqhVJbWv2L=B8-{|PR%0wb z5hhqw|NZe4P!pxvtp?(F*>nU&M3)1v9<;PHOdGLcA!M-7`0&n`h%q8F4&^dGTiVZu ze!!o#GyMu812Kn_D&n8?NefQ}Ym;LS^k2|Oj&5T2R*6-JdeQT86TPR}MiXTkQtLEvp9 zofCD*rDS?UM4G|IWzgXz<+A^&u)9gw<2fZIS#%!&8-UkNi7*QCDt&tHR7w&Ru4F zFubM9oYn6>qYYSgvqi2hPnWQUODtQ?a6w)9vt(-qpeCTocHEngo=VbqsXJ-WVHJ8(#*(etlp~l((^=jZkESoDyyy9u9ohl5N`9 zGOB++GkYsg>uBCwT#ORt*kyJxaMmO6iO@44wb*aY3GH!dcQoKve;Om;o$XawQv>;6 zyU>|T2F=dMu=-5O)b4HZN70AEvU2oH8oTml*7s9p&$+S7*s3H6dDL@CN=owuQDAZ7 z%X3i`0e|h8mOXk7cp)SDgklG6Yd@_G{z7UXM{9ap!=NV=v*C|$F^>-HKM)^xch62& zV|{kQLEV!AdF@)`LwhmIr%#`j#0TANJoH6VInp@>X@=j3nk z*4UEN^I$M+_{Msf+5K+CqOXxK)p;8=HMKZn^nmOOf7gfsB02bHIA}EdoD{Qq%)ICe# z?W4IMP0m7_{ebOEnUmX#{{Dr-j>m_&!6;YTZ^0mJ6+F(Nr2jH|-jTyg1EULdaK18s zSraFzb#q%f4d7H{hG8LvshiOUT!9L5{AWsQsoL>&JX!n^8QLQ2hEmIfh(Ql)O_UaqAzWJ(^V#C1rw5TtA>tuoaLjPT1z`#$kva-DQqXrrr>lhad#}^j-Boo#B zrE`XR#;M&+!ZxNm7|M4qLHvE<{J&gMoqi-2>8_ga4mbNDvSl*b1NPVZqIdibnmEM7 z#6GJ_#x9Z2#+j(X9_d088$wiFw%PBk?(TRTVP_JlV^eo~WJc7IMJcwX`3 zS9FlBT=k1Nt&Es(?R7CU1Z}^AZhG?!hgOl4p1tdM1ME$xVuTfntH3-);VnK(FK}%K z_ZGaA3nTQh{#WZI--|mr%do=2{WiB-D#Hqsx0^{2kUUr7Y&wcIKHgWBA3bq)+-VoQ z90rgb$0-eqCwZ#dEtEuOmrS@W4UX7u{O3h4Y_vgd`>Z0Dr!N7u=WzIAjg8pp_VwW4 z;ML!T6?i{iEDL2ky5QBj1*3)4Ta0}f){{EnN#j?a>n}W2xd2wSek|Tt1QeTR?S~r~ z@&5Kfg~sTAc;SP4lYuo5~CW5%4{2P?szH+2v&qzXlO0sZG8vDB#z}8cpuR%2pJ9h@jEJRfuU);*Mu5|z2W_KauWC^9WX*x)CB~eDl z$Ii(+X>8Vm@TR7tv!Z9Y{#GWWz{=G2uE*5m%oXs~)(-DHmv;Xkbd_O~Gbd2#=mLlH zbyK3^qz=5FfkV*vhucOiIyg}ZOm@6C%J$WL*l0*%=!CGw>k{3YvuqhZQR^|G5lFU4 zBI+jxppgK&N4=wak<`oOrnUmixQ)*Gzw)Kw0v}phj(@Sm?=OSy>tYKV8ZK+eP7;jZ zL}h>4!b+RcznCI>)^48_zvF$!;nw}O4{gME8V@)pE$ew?Y~ z7Zh0On$(qBZ(hHe0e=^=<;P-QTNsS!_g)_hq;kSn!a#ULq26NFSS-`it$iMnF zO0fz{h;aaR>OZBFo$Hc`IF$G?&2^FwWO)NA1k$7wHd+t)26UJ>=eXfLu&K@TGzC>5iS&MHy zN}Mt1?)ZQcF-QMFFsoa5wAFDT$<8)BLEf!?==jMD6*ng~r7%+vPnM=L!J&kJ=<-9! zt(=5ZpdAr(;-%>sKLQ_(Y=*8_#QJFRNGWrGbrO&JrTfM)M^2-F z;Mi7vN5^B~VRRVtbAFI=m(MxzwaDB$cL@N_+?M9lOLm`$q+Sj~Oz#zEO38nD$ml0y zE8=~N!g9N&r-pqQc$(Bw=|p`bP5Q53g$TC2tzbdhYfJ?&1#x#G|$L{RxoEW_LamYYV-wUuEGv)rd zUUzr*n9>tC?vGec9gUORNV`8`&EZ?On-Y6=new?hFT>-nuYFuJdd{XPz`VTMJAd(~ zxs9oS-3nCkc2@vMyU_QjH8kxl98y%Hyn!t(q(AK@HuoA^sy3~k5#Grxuq zDHg1vE|t%akkpqS5c^8HPKCqkwj@@D#qB3lUci*}^l<7OdoJ%l@7_y(53x(XdVD~d z?RV@H0dGMdBO~K{mF>kJGpegLgOjcf=+#+&>8e>;77Ze=(F$4`t*%8N)Nn2b77C+b1(b)C<67{K-D1TSeWAg0nmYw12? zmmt`5HTuFOCOg&uM2ClRVrdC;O896*2;qKqap{=mQ<8x{C4Ab>x7K7jL(E&|tKCm6 zjcnnWG@`_r5+QEi+W`=vMbAvI=>%fX7M63mD_soUm9cSx?;jfzYjQ&Q@^o-^u5+0~ zCJ3=v(cutpLEE!ebE1Mv2L6}M4@O1xki^t2ADQr z-V$P}CX>U!F-wD**-LCr;*YT1=J#m`Fb}pFM@(Kt1!=tW$*;I2zx=?lSoMEW{;D#P zg_Kql^Rq-&CC$ubUl$w>C*G8yn?RJ%NOt0p^SBov7J2;RjEFk4QKgAZIM{8#cu5qNY8Fn~N-*oJhJaU*6OK_t8Al z%Ga|V9PTpp5TGM(`+aqJFYekIs!H!=!DpEMgS!(9Ny@tD>L{v&e4!_VMUm>3M8Z z6BiPX{^yp&EZK8{Z$U9as!w8S)Si={&KTD&tN#O%K^Gx&6NFTI%LqFchVJuRdr5x; zCJR<()sVj?i~_2w%KjhFMgr~wyzd4%oJKC(#mn&>U7s81rKYfpL| z%)Wr+iZ`%6Jx#W@u(ic|+~ezLm-OX+ke z<9#LoHL7`fpGGkw<|aa5Fm`oKb=EX>OC;RnYOA56PHG6^q;cchatZ}2yzgZTt}EmH zSu)Kh?9R>(aGUhf2Tx0f)_XW24 zV`>Hl;*(5hm*@Tv%c3iWjTs_vOk2NMn@17p(YRSM4_Fc2TWL1U1wuATF!MZmTkOg$ z`H6HQ-4b~PQ!WoP?iqRpo_{#ug?+QNx9Gld%o;26+QKQGc~apS|VNfFY;!}ToLL;HEX;0 z-#4C?AOdfM2(1cIa>LQsuqYJlGcBlB0eKFBe&@!AI=_IxBg?VAl=LKFjEpBbI0J8f z@2IA=vXyZ_dEB*a>s-DsX)=IqMbwTJUaFJ8dG|}?;C;=w;ZY!fX1a!zNt3PDW{sRj z(7g|3(Ae)9jD67NRwk)S%iBErz1-#()Cf>kuU!uYjVa@` z+axywb4NF+GTI;Du0nIzI2ozrKP1!Aaoa*THPtmbI_)kF|8Ecif1`z}V-{YtPz7}U zM)+p{E~slZ9T{IX@4jN2W#VGz8E$5sG$dU=zRG`BE#LDgUxeh+BqIca8A>11XQ}qC z{6wF!PeP_U*=dWQiVD=}lU1$aD{#OI+ zAiX~lyu+pHkDt6%X}Y#?Kw+VpmCEo{Ycp)C?x6U2;{39DfiK^&zSG@tSO&G_uOSzxhRa{{UAY6`;7dJ zTz>m@xT3EtwUvj=%ZMALybru6d$sP0@@ePTccgXZZMPC^th1P)6147lPjHLnHJReu zr2>K2ZB)z`eNu5037!Pr&vN;^6G&O$o2Jebup#mkWq6vI=&ItNB)Aht`bPmtfx&wj zK06ZzXGhG%^q1uGfO=_J!mmQy$LD3X)1N)t^}um-m$Omo_05B>|L`8Comr101K$eS z3Y|ezlzwv9i;N_QP;l$kWnZ%Iql|eGG&DB7A6cct;P1oes*9W`S(G%?@)Qw14|hIS z$+6*1p<(jA7_`>osW@f&N{cZwZ8<`g_H23->(jS}Aa4FKW`8CktRb_2|C);?Nb9y< znq3bWZES3)J|_n@MkP-f*k@{To}izTdgGUff|P-hQu!5gkvl`rciqvunVg56oC8K` zYI&f%PjD*=3EM{ED5DK{B=Aw@apn$;7@7#O=5zgc-6P87RWp6CidiFFE8(xf%PL} zD)3P5+vYCOP7xA>hk~k4r>;Ry6a;5V*uvnw6%}Kw|(gz%ynXz^p zmvz8j6u(dqA)Xu492pzI;^Q$XyK}yGkr6w}ZjaaJ!5I?=!7Rz7ErsXTMI}P=W`j6B zE_kjk4iT_hEX;j!j^8s(+Ymn{ZSCe3zX^&zkrCTRM~jJ%4YQ|}MmiGANUz=U6F-Ft zipLRhVN;`44gbi9b%zPz3~_S8JY>2f>e(tF-4`BB9xO_)`=dNQPOcw5uKAoy0P4c- z;v8gLgdtO)QNyMG_UMgl=*5MnF)c&iuV2_#tVe}00u<4GMX8;X#}8zR@+Ci83ggN2 zhGyX+RL#CU^-yMERTiFCuP)HVue(wV7=rGvtQbgTuU5MkoI8k3kSute{`fuPc{`HH zDaoDGxEn-qj%;b_UB`PyvF`ilNY?=duhqwUrpJvQrsn&4D~~q)-bnV8VH=OvxJdCr zvfLO&f}k0^lk{5!7&HMaS}SM{JdObpptk6LI{ItV4Ja7q(nq?dkkeJ;*V2ri?b63R zFtg2qNY(JVjyDEeFPFSJE;?;wr94jl3}Sk8*!D(-32glbs=y;JXK$<7LT?9^M$&Pj z0bWJQ!@=Q0-2OrXDWIPuXsg!MDT)!hWEE(0o4fkp*Q3z(5>~1m>5A;~0r|V4^#pXW z_L)ic35{JZ=v7=CjHcif5MCSV+?lD?4`l!T{W~!}g~{kfyxekC&|{!BsH(B@i#IC? z;4!7Y05~`KvG_KvY49gIwK{VP3v|GR2R=15BdzZqKt$`)CI8*-1|EMQ?m9Vfqwg{h)`s?SD-Yo|L1r=?p8dMTAQ1r0jUD8sw!6kAB8q|67$d$VppR? zSIJ%wKURo3@(Et<=E>EcfXj~KF{wj`idziU^lWg+w5BS*XJt2Sth)!Pp=aOP>E`M6 zKCZzBneDy3;m0Ew)mtquQhFphQuquw7|F<1#sYjARFWgSWG^)>4M4txA8l-oqgEdI zP+B>@Y$t_Anf!g^SjK#MPq~_!$!|RzU6a7Jl%&ny)@*VF8V(on@y-3+$c>R}YWQ^| zM#hSGjYSrLPK@oSyov^@ssE;I-`1H+G{k&n^xcmA-XZR4v_wTdQ48I3$lu=fr5cQaihfvUjuNho&b)A?-@->2V8f^uTzqaDFm zT`b_SpwI-7GRL19!arMWNLI#2DFy@hBqy`hfpcizvr%$s z$x#h$#XgcqSwc&)gG`!|YIW|F>}3-oOWbq+w~2^}ywa3_ganNq_~d9G-&od*8^(-e z_Njh>N&NDt$2}V5dz_Zm)IUsP9ComreV6lio#U+b;(KmP-iHN1x>U^5SCURss;+}= zm76O)ROdBkN5|ER_FBEb!NI9)Z2SV)=l;iQe0R^eKmJ|>{0Qgb7~=0=T}|uRR;x`+ zqD7u@>ki$&3VJwOU$;EO1+ZroJla)Q`hNT$)p>Sf3g5HqNWQ=G$#%q_#>>?54utjl%jGp|}Z8AKpBI@dfN`0$CJ@ z^C;!h377tXf&bbM>0aK-zC?}Z3OQ&XYE(!;q4#cce!khHid@Sw5U1DdEAe-um*lUd z>U*BZcG8@@$EU!;L3ZH-5ZgsD&%f#8(o#|ls3O~n09w$0QhgW2hb27Lg@?|DrKAd+ z#Pz42ABK&JHI;lON4xvf3cNybxC3K^f)j=%8%21NQ%YOQiQ7des*@GzP4xAD^Dh`P z+rE=>`=dG>#~`&TP9iBKwI)eojErzx$b|xZcuF`?_4!)!d4&?WV(^nt%c?K9jNYrg zdjo-#%3fmVK+x5m#khUT2G7F`MwZkDagsnz?<8O50}}k>*_0N?#ovX`J3Ds#CSgy+ zSaNe|XpPsbni5{;>Hc_2W+&n>jKjM^0myYnt0>va@4r;VL<_7^Cfg5@&xfmarT7=q zOR6oKIjL?Uvsi7$G8eQ>DbRq>D+my{R0rAvZq2uGK7Ra|yC*5V@&@pPxzoa(sP_b$ z^V$j++R0M0GqJ3QhMVXguHqlBI4T~lI66!&qu)$N0H#nITBLnqztMvK_>r~|JopDz zw78U@m{>#JSRTv${e85S+`YS+jScSn{CtA?i?!xgAB&1D3@GtfT#$J=)Af#cD{o$8 zp<~KJyLYCFk2m>(u0P8GEji1>OkQb}i-I7lZm6n4R{HIi+#3b1aX0ojaPT2EcSN#v z-OLAe;@p3?=cG)IB~2Zt&+-W^lAoW<0WVb1tNg%z^?7R8Ze!PI=cV-7hnm#v^zMI^ zVm>P8k@eHN1^LVl{z)KGYXPb@oYnrJ9jC~`KkJelL6$FlAb$evHNV%zcQq*nk*10dbiYCkv> zRb9q9xjygtY;SKXvE+OyInyOCEu z4?4_@G1+p!wEeqNg{s=y?pHE$0S1dmBFbN~u6FQ2;NX^Xb zEtWekd0NqSGqqxv60Kq^21JX)z(Z_n#98HeD-e-VQEkQ054V$(V6&MrI}G33Tgn`t z3!2mV1*g~T37_Hi=Ft2EgkCy!A<@ua?}uYIiTM@Kz;jE{4BI(<6d6O6{rG0>3S%$0g<5?Q6h!W0VMz+IOC z_W(%HSm9`XUoEo)L*)czJ1>Z0jfsya(a*tol9Q7Y5S#LKH(K2Z*?5wc;sbYg^ul9# zLUD6V68<++IdSRj8NvS*YyK6o+OjOsC%BQeOL%4fRcQNN;vW={G`iHg%^X#-dBL0Q zeG+w$JWB~UAc`#UWA4p@Ms6~>%;Vy3q_cmFFwY1R*E?U{~@pc6z<+ZQWRULZDfjYXodE?rn z$vRMNAth>P2tM*>iXpqoj`x?1{|tCin^VPFZ+s?kj{YG%FB7o?agvc#8uj}Vb@bx2IQZM0`-yEp_3d4m*f=qU>G z8|VTVKOMb~&JPa9m$e2U2T6niE7B7Uphxk{_b^be&R>Jwh~DW z1o+ADOG-OJkk3_nB}l=f*|@N29i)eq)yDU~b>0Ub0UL+!vD`VJ%x@r$0RS2RjQ?L$ z%ZE>6LmM0-@KvAZJw&Ja5(wDG3XP18uGQq+@7wESyWe~7l{f5W*Zo)ygL4v)m^2?= zzZvN77qy-l9v>e+J36ZLnbHtrNf}lUBIb|H)8>}{*16#W#yWj#aBtH?L8!c)9;Yh^ zghGN5{x?E=D))tZJwX1H7cFwnCpKM|9G|6=x}0K0NCklF;@*LO){COH;e~)k=W{mk zMhFuV6Oa#*t&>g*>1k0eCSE3nGibTx<-~oK=-GRn^^Rx&f|5P^ZY39s@#g$bZ`4!V zS*u)+85|HzgxM@7Yq&fC&FnW>Q~3T0^k4e*V0)sV$SySjl&8!6&fV+3K?*}dBcye- zy#b|rPw-KIyN#f}sd4Z6Br6G%?A-~%REm#Q_`>yc?l94o_?aWZzmW@HvB!;#j5vIyUAnY#v0XSj zMaUremRFitOOSbu=~rx~ySn%>I0FL4wDXXAew30J{d@OF00>yD}I?yKviqMPD!pg1$+;uG-#8Tk45sMO^T-pZN_hRyObn%fCT%k+?oym_lNt0 zD+FqDME+Ef8}c@Z?`4i&ba-euhS(WM&JMQ3MU9I#Tzzzel6$oLP&nhdZ!>TR&Nb%7 zFyrJmeRL{nX8OhnBU7Xg0H|hA%`)8y& zt!74r=VR2=EYx&N11ariFsh)Fq4)x!9o*HsUwx)4m&EKdl_=j;>0ds`3=e_v6Muq@ znHZX_EBgpvGF~e6?S#q@EO=+Enb{6Xj z%cP8a_p1g3y%t?@e-w39^8n=u>%K4@2LV|VKWAX3C->d8e1*&Y%xzfWZi4B4;#5a& zXFe@8^*8GF;WQf+0w(AYUQMz&n9gXX6o*9d! z;&qD88yW$WBZ@EJI9l%RIG&BIjgkt;bWUB~qok2#oW}FX#67|+cf<*}Cd4dQz{r6y zhj*CESUe?R-&q>OMyysBWw^6DmYnT-Q}VCG>nBG5`P{fT%`YeNNME+XaQnG&V$AGA z1w5t*Mf6AuW;4!JKp%KmLj*mXs?y)ehzH!9ErY9|B)3u_CzUVzxv?eAiwrkn8UiIqkj-;J- zz;?D0`3EYX7}j07*u&MiNzN|k9|Jzp8HZ7s`TD3~#iE%5K32iX&1{3`ic1f%zNx8- zXa)d8!comGCKX`8k{!u!C4ZV7^4vAvsIk%%nFpS1Ftt_hr2nl*@mlslHEcv(J#l7G zT6< zxx2NOe2=!nK9g2*Qh_Olw<=ZI{w&i}pM;6U#uwd4j+O2vqN(_nC1ive>{?9WMbbI7 zEp0VVRd`6W2zXG0`a>vr5n?EWhw8+`?2UfQu=pEwu~6xqX^Qr%KEC$KB*U3y@%!0! zK+iewd*DZ2HPiFWD)tcTGE-asu$!NF3J57$1<0CgB4T0B#?hFpcoU4=2V-%WNn-BfoTN0m&EjEuZ0`yj&< zJs{5&;W)QP4l{|3q_bsx@|h1E>5&Jue7xi1bL3+COSf%C&&W6iWE{Hd9e7a56Z7)~ z1Fq&$7rR>8?9K2nRpvBx1#WD_WmRJ>9_;znN1Nl7_PZ5P4}(=$Rn$d|4dOvExWEGb zJwZOrS%&sNuVC$Er6X=Lyz40eaJ%eQPGf_7j?Eg>KTzQfVLVqiu&^bH+Xxo)?S-^mX_?*5C4(|;{F>EzdV11;R1*;J(J{%J_LF^%hOfJo z6gd7yJV%(meET{OCKJbrtua+uTN}>jzedRCAj)=+3i8=u1bnz~^6f~|9qTPxV4!nv zvb>rW_~NUDLDscQRzSvwt!dNv@I9ylP5yDUbMaqln2j<1^-JV<wVw zzZ&L(cg=x(AY?e?o`bGw4A0!cDchq^YR_!t{hPpx8^ocZsp%Mj8NEpfY^G3p^5_|e zB~RD<2Qb?T!QsNV)_le(K*aaz6-m46O}XueY1rI$zt6u``|r=VVR4ZIpFb9_y?id5 zy3Br;%bb>iFiom}5Vs%7iOI;c?TyTx8s#hV=3m_HpXaP>-nOqv9_XNr69<^wNR+{j zaX_j*x*0#i>+tbu+lC3wwZlUMJl+4?{W3Xh_4D)#OQEmo5H~jKWcVpJr;AO+aj2QtNm0x6)ICJirvDP))Y_ymofC!UuV;2%Q>w# z^F_Q0(LdsjkB^r_!tf&dB+E#qdt1o61|{8re+Mh* zX0786bv+mHHPgb`0nVYv+2-PzeW2+TiN6m|{A z+A{xdB<{GX%1HiKF3GleXdk?sB{vIiz- z0xPv^CmRB`ldWQnot3Pv=Jw<|UgjW*BNBSh5U$D;2Vlp7`mi!quo^6!rF%4!O86GVNnBzt*2vc5C|m2scmy>gV@Ah zX(=^3TNKcEa8%xK9RA6a)8N8I4?D#E^ra;EJ@hL(|MFeanEk|=LcaDI7mg)ysiVKnMlxN2;Y=w=lW{UIYdFa)#x>f} zS5DdgI}sT6^!EiC*vi3DOOP<|SlSj*HkPv)%VwencAYkNa<-5mVlnhcYf}PG!x{@|1_2bVbK{XGKYn-0LvozLkO!qx<_?a z1%a{HbKI2!{r`Qi?eG4N{px7)CHkRG+x!}*RxryF$J>i8Js_7VGrwxB@^kec69Pmr z&)ar6dac6l{`=Je-6Z#n!)v;HHW&eI#Sd*~sBV|i2SgZ!LYjFl`pYL;y%t7&VVRI( zAn@m|8#S#T$0Qes`qzOpra+me1wfGolORsJBtBcm zthYy9{L;4nl_q3^!vP2g2FXd5#&VO}=fVPsA@Im=yJQ<9JG;A*EkP@>#dK}iu_Hh< zr^?yEVLur9Eu-jK+=?i>qlA#SlwELqW;GKC@OWomx*|L_cGN#UFFiJq0yg{pKb1um zkPl_j)W_0_u8s4wgZG;GHJ*YUcX>b6Dd9BJ0<*BE(!G{1$Oi%Yv`H#w*ajG5bO+LT zgFrxEX<_B^pXReHA|g_Utp2Ghm9tTx-WQ&Nbdl(C?Q!1v*MLB6s)ZwHjpO3^{s z!@J3g-K%Bum--1EG+6p~R!qdaBfh_<*5WEcQ!+lJ#fC=?21K{NrSaEK5H5CSC? zBa{fvxua=XNz*j9T&wC(N=3{xbCgm+DHQPbb%AvbqnOyjNN+~EAOp&`Bpuy!bxs?Uy<)0Oszl?4}5E*DQpcGb~GgcbU%D@YN zD+~<)7-vvYLX>B#0;rt%Lb0{*-;B|U!AcouIT1>)Fhq5gu|`JPSRw;$Fe@cHLeIDI z5fU0Iq4e_S<8D~;v~ z$_7kHa5yFGvXHkgMdfEg!pFgR5L?C4>;ra=G2r*SgwsM>GZ=H4`)z1qG0+{vEQ0zfI^#f%i71 z)eNliRdV(JSMT}%BWep-<^IPvgZg$v#71Qm19iC)QIswsqEW2kK=sIdMnp6*k%2}; yG%=BZMnp6*ysx+S-#2;@5fNJz1zdAH=Kl|23v(#%r?K?_0000*b!k{%J$e5HFDK>1 zeXIRxx7YIvkCRHszC{*kGCjQ|@~mH^Xuimg;+aJpZ~kOysaL5=J%b?EXDMw$*>fMi zcs4yZp6V2tkX{NEmdVJ!LA+F)krJ*_UWjsP&t+vU;40tz5O;lf@$CJjR&&&*n_SiG zu4}x3o{32o*d68*Dt0LF_xtZ1I*GsEC(hvg`6?7kjrHfNF9{&=^kezv%%5-6av^_z zti>b#^VN;_A@-lIM2!C?J!Qo|p8ipZe=7CQqA;rP4^aMC1oRJ2|8U};JNc^;|GeoR zPW%fd{>4%lRrnW5{>6rWq2wP<{0k-jg_0Om_!mn4#fE>OzfkfIC;o+!|3XQOD*Ov2|6;?xQ1TBa{)Li%RpMVL`G*t#Ldk!j zBt{kfg_3`<;a@2EhZFxo$$z0FMiu^rl7F$`Unu#96aSAx$-~qR)40;z!nCU1RZDma z-`Ni;*p8R4t)R9BlW9F+Dq;OBx3UdRB9@5sDgKKeYPWxHs-hgo`T zaW@J|Bmv!Gj=3GC0?(CqmyW*W55{Y#tGVW*=-?2-Ey*f1b7gq2KRq+EXgVc$`0yv^ z*utVOl!ybrmf2w{tK6g8hjz7{@6_CNSz(r6M*Cv6XU`R#=*p2Wz4aO-jPbRSrAroK~E^>?@dypM~G4N$RQ-d_W#};d>%6Jw#-ioHJ#oQI#@W zq;jWnv#+%r2aNfhc$ioxsH|+F8u4n6M?K~SU6$${v@W5~S;&c20-|1aRvyV8LJkfN zlNzyUI&ve);h9MZc+{7ynHQOx#VO$F!QP3w42$Jddm04iHgf_4V@{3_nl?I|s2pb0 z$F(us`pm2D^mM7P2IdeM;1B}Ps;4YqUue=h#9Z>Nt!d%`<0`C4p5B<^4^W-U9i20&Yg;wG|SBk%*$b^iYlXm3Bk`4E42NR+nQIG&C2G2ksdbKo2C($dRo?k zZb{jz?WSqXk=Gc7aoySK+u>!wFyQKJmPegnjEPBkSq7{vXMncsWCH`q&ct=HMen5e zCv3IDjg8-zGl3M8m2a42l~V~|#rKQ<`|o5{k$%K7r*qOZFY#KmaWPZc)vJ(>4= zdjb#iUcMR^Ri>!;A)fcEO-`%7?+3g)eD@Duy~?u|O29nqZFw+P57$Q?h$r7U>Pa|O zK~`3&b6Q_i_L?7bI}|D3*Um z#|&g<_GK-^Y!-F}+c@O8bQl%~sr2j*>Q)@L2A>r6=Card1l1s4H%MPZ?WZYfju}$@ z`o$WXof(HJAAGZV?)k#+=!?qRQn-B;`Nyj&wQz%~MNE04GBgf}TOJ|-dVBu_AS)*Ha$hlPoBZ>10g z?ovY8Awo&TaDO6iuct8nz0&d3Iw16q;~gJPymK;d2O|xtYRCLten3Ewnaf;18znl8 z@kH;}@Cw6%S; ztYnKYZ70#eOEh_NhTt;W@pa*A3&woMTR>`6JG#)2dZSC#&>=ll6kyCvI2RacI8#GYqKzZBsMl zoYJu&Qu3iq6E>BeJmnsV1Rosy)W*ShoahhgPjfT-GI{(_t=(=brFR+V_VzZSo;!5t*vKcYI3yp zuB3s0;-nSq<%6}>fs*Osw?)d(R4GqL&)L$|?qJ=O5F7Z*m=EgqY2*(s=;8mGNT@i2 zmpn472!sPboaP)aBiTypG=mV~VZ&)5yyL|x6WNzSsD%MrD zZ^;>IJx=u#y-ay`U&^DcD&(fXrsdQXvlz&vxplFP9_`79)V1DwL@(lF-VR6Ob zT+A^gu7$cIk6e1@?2eOb&U@G7jJd_9Y%`R)ot3AAJ$%=*)#v4t{TaL#>x#B8FTu~h(ljj;aqCIw}v+wnc* z12gp(keeV7zI}RT{QNGj8;-WtHMGXj`i&kC9dV*K?dH}t_QvVhf`jB^WhrYu!>q5} zu}{sVA`v3|#)W(!0CS$^E$o40e(gGGY6Vv$_h(-uo@}~7q^3}t`hF>8xdZAwpRu0Qn z7Aq6l8t8&Oe~mjL2S;Y&7hN?Ic87B=$rj#=bh=binokv~;su1J)mK)O<6lUL4JF1G z+1i}gi8?=6bwO(t;)`XXqGQhWr)gZQgtY|gZ2ls&L&Muj^ zrK<#XX01VAj#9B?$t}`v|;Qjk-!6J)t*OVv7 zAjQviBZIv|1(a_#i0PF++Pt4o=euLj}9v!F$YwU`i5trKEhOaT7#7@8n~s z{tBIri5@v4Q<3{^TX|6pIxz@Jr__C1jmBqWfO>TK<@O@8SMp?iiS7jZmb~P^`A#o* z1F^i=TfEZdNYo@BqEH9+E)SlG*X|=MRYYUS5Dg7;F&1(PP{Edss52eyX!$EMlY!mt zz)cZig-2zyI?|%1$fdrkNG2>uDK8%v^_&E8O}y3;VQDA&#q-casQ8J~URqAFwF7xs zm7OI+-dPL$2Rcix&qSA~&@O<|7PU*F_s`(*_4an`uhLG0@owStyv-+MZ8g4`ct?N& zG3I}Fxh`f+q%)I<2AVH3SlVq_ucmritj9?JLE-o8LWOIS-tR?-i&~5RYJ5qXNN|O2 z;seuU4bqGvj#+nWbdcL}&IQL!>IN#&0IgkR{<^@>g@nF49WRYJ_A;Uh;p3VZO%;@h zb9?rM=#fbnDWi-pQ7#^m9xL3s_QHc$D-awacq=ad{P{)hCWSvyu3v|fY4dFkQXx@( zBDQaN#eB5Yw{Xb=sgvYn`Eyr(pUk$Bt|0ASYU|new*RP%sQziuJBh`|gPNC)k1yAo zUrgN)QB)V7oroVP@7;a9e7G#Et*1h^iB*)5lw_Hn|5aaAL`3(su61+p44Z(1boys3 zC_QAoOIqCf+!%ZRkjugg^W6ai0!IM%*nhxrVmhC+)cx<|4g?SUnj=cGh251YN~9znzVAnMRffJYDG1+TlUlA6TG&pvdL~ z*3{`dJmjpfg3>eeTYq?a*Spsbv<$tcpEr);K5X^%MO$wsj6^T%fiUdnkYMS`@Vj^8 zCdmr+jcdQZo7Au71>zHMT_PmV6QEQ`iGIn`@Qp;Sa@Pc0lJZa6+>WeRRjd-|?{gY@ zvFgrwk&X^t$Z%(P|B#M0I$E95*W26WQlRWEy=1}S4W8q9bgMm=aTv9GXdqfhnVizK z=jU2`LG@aD=(`{8d?L7q(XqMEwn1;KgV)!FxV5i>ZreK8pZOxsmv%s)XsQKgMNxlY> ziJ~zEeL%7-;!=UuPfS~!lG4PHNVsqVf`VG-QxvFX?x+op6s(n+tQ=LL4P8=l*PVD! zTU}tdD*nzkOKvx}n@u3H{XG}g4o_?J_RqcJB5!Z+!>W^b^j=){tVazVu|)Xf0`(Xf zSIZf|9{c>l^y7uWuAWGZGXCfGD6_rI?%%Ly0J5%C7N?JGvg@nG9v#VR9dy(&`coiS@~rX zo>zkw>bJChm+~$6!FrK?RgNtsUe;iFenI+9#Z57)os6mDqFmon=gHJdG1B|AgeMB} z*{ohoB=p}e^X3LU>*hy|TQpZst}svIrufdHo-U;SQWD>K7Z`Kzi~Q_G3Lf#%41h{* z&&Ic&7(c#cBG1_L`{Y?8;jw6d;2!5)E_+3^yNjyRn$Nd_;>!h$5^i?^^BwMjJ+BOG zUUMz(rV68dB5-}&qU#{ZD0Xrt{Ut2L#8JMAFn-{n-$p!Yuq|QXUy07h77)-l$5CB+ z@!qS!&-!IrM>FbzCnX*gBdD1lRGIIJQWQqc;3;SaWhIkwaowwnoeUc5;zxBP$j;)X zSZ1+(wUHLhW*XB|?7f0u25kB4a&xTK(pnFrd+eNmEo3r)E#oR$R`VOa{lxRgB@#rw zE?`Tu!GWwRx+3A|H9(D%7+jRZ`=XQ(^EYRHMoliHf3iACJgeC!);{ z2$#x#dLVy=0eXf2J$2-&4L00uTD-$R5LK?n0_gPuE0;D{2?b~)!WR!^yDV?;nDuM5 zn$MN;r3%BA6e2IjreF55U}sALre?yoUo~iz8%LjyLHlF#$qbb|)pfFO8R+koSps`C z9Z%ISY)gkgd^4r@33y<+%$)Tg9P>1^C*n}-s}shyEyD!?3DR8*%D!lGj{!{K12gsjmWRbn zE;KPNQiavy5kH?R*mYSb0TC;@-qJcn5r8)IJ)f`Qi*u)jlOxv~&ue8%E(r(AKPpFu z`1cg=10uhHykLg4#z=l3Ix(#Nq%4DoUZ&O3nk}^&Ty1u1vUHs9)`QnSgC}k`Fm^OK z526KhqX!ZOB?aj-ctXk!|Lvy zCQEA=9-wsDB6~-pA^-{S&lUT5$PU5ozC*2Zj%9MKjuG9l-CI=#jEa{SN=!?I{U7``=acB}F5~2{gj*B|yL>Q|UxZ4Nx zEDGd36?ihIOUu@&!YX%GkQv@oLaCx5?3@_DA3?ns>j5!OM%+{qX3D0VXL4+27;ir@ zxq7gG(mV{}%6mZa#&iA#YRw>V_q(~iC8}lciQ5Oj>41zaOWT&sYXog-1zRLq$84(T zM|_o9(P!|cAFur3m{5_#GNC913J15Wqu$I@ zs`j<_UuN|WYF;Lkngnxj_xznBCu(Ir#o^iM9MKCNNT4lx@*$AIIr00suX=~~Adl5B1OJ>WuJ)hg7pnbHxR#H@kM{!a(CKjdA{R3@on9s9|<~1>}`O61$qhSchu=s zadsDw@mx?=+xZA*sNs(cc>3ql^uJ5uVR8T6Cue#95~`;k1v~Ke=_hgNe|OIZ{&%Ci z;D49T_5XLJ{QsO-Q?VCbTH(Q+vX#_2ME+gch~Q)FPTUmw<#&e$+RzH9&L| zURV2)8X@>w$hHhDmFwrb%uyEeJOC=1UhwU=>#*e+xp$Qk&?R)rF?)A-o73R^FMPE3 zg?*u-6)?^fjMI$YrUvtLQ({=(26JJMZh{eEX<45P&8uBTXnlogv3UlQF^!QRHHM$p zG+%ec0mRNWz`DEH>)USyCd>Kd2-i7`Jz$n5wrbjp$TrjISO-*I$LlW9N36dGyO@v8 z#syEQ(HN=Pnl4Gsf$)lUNYd?g7mXBn`$g*M6Jr*!e)8nQNh|_J%+F${KT8BaGVj1) z5{L{Vf$k45X_meSw+s>n@H#sytT}G?X~m$_4BaKYE8w@NyD)V^E?>E6RrCbTgh~L*oG^c!bTaSZeI`Y>mzFgk^gl*Ce`{7Q`v6FGON}8<2YyNdqsAL+e#CMS{@c7P`i^AYVc)UulJAd#3)9JFYx2Wxr&$LFZV~)SA4-$ja^79!I2u+|3r4USXgxLMJM4LXQdQnf-{{VCl`4Q9oJWU}pAIvr z0F-`n#x0iYB9Y3Y+G!3lN|vndqBD3(&%Ww<>hAZ%=N`Lw)U@$e<{324qV}5QMQbB$ zP1JYOY+c+~G=Mg}7OPb+jK@jG18Ikw^^f3_{dzUm|E2bKX4Z&o6O0$`kWH@@?TbIJ5rp9kv29%sFL5{w4=10##YKf>+dIu)Iy)+53N)|cjCnz2X zg_{8Jk|!gCos`xtdnP036>ceCrjvOo9#D^`uEV9!uQAXF-Jblo_-c^ydPNXqJjk%? zx>XSai|La2Vf(cRdP%Es6D_-i8>0scg=oY5&bl-uTEVCQCK_O0`XTg$k7~!RUG!p8 zUxq@c0PAma+mQ)7iE6|x)4w@$n+}(wT948)IM7+tCi~)JL4t8Km_c0 zS1J?-u^vcoRN9e&2lc=nMIYFg>Z4j#04l}r$!R4Lhpouz$R$LYVEE~CRqQng zM$8ED+Kqg)#&v{$!^t<}>NMpR6WqjH=X(TkOji*3#~695)Ic%~LxNjg43{ol%JN5C z6U(=^6g`^BuM`Ut$~c2}C6r#vS7)7b(Y$nFC0iWp_fG&D${)!@JVD1nQ%1dxXCprm zA_o0ixw(9%HGX@#`cyOK=x(jkv zUwLU?1>Szz!hZcB_Vg1*4q;Kzqk+}fzQYFwad+8hCw{kEtgly$4DD=fp$cDH>jxQ&TjKZ`K6yV#tubLTjlxA^AlDs<+n%}rh=(y7$i6RbduIq^1dy`ITcc# zb$bky0v{wuiyP)L&ifa{P0gLb3lpiRKmUH~$cCi3#09zg*y$XT2#D(g2K5jnkK{(b z5Ye+M>UiopWoGUEE)+OMjt%vpQ3P9rBd=O;^kB<)M(!i*;a4R-H8o}i#cN&3M-s#p ze|A`U-GSX5l{bv`?{#P?WD~R;|JE$`z;%4Tp)FykpNIW23}2Q*@h%zP=5I^AxP1oi zxtcD)3>SK7sV7Wq|j2Rf7kT^Jnm6R8@eQ)M|}vR}2F=T-VzCjQ;&wm4JZ2 zykG_^XbC3z3Y*~g3ro@LpD$@4t8`{DdDVW@-s+pP5^WgA6C8syXaP%)SydnLUHi85 zi9uRw-|;bak7!6pKK*{}!47xdOM!Dj0w6B=^uqK}P29UK9$~Pwcmzi^W7Vd@SVizk zbWHDdr!OLCO4X^1V0der%BFU%WxWMtgI~!zo%>nsS#+Vf!8Ip9Wc=YPIcjX`zWP34 z@{?w%^HJ^?K=z;E(sG!nc8FxvWZzwiyrb5Cw`=v5RN}Mq#F^DDbvo;;D!kAqaL!cF z#^hpcw2WSjQ3DXX%^^H3TM()v9#DtJLB?b%>2!xFGFcS&ngJ&Q3Y&`0ALD6A>bg>l ziQ?K`lBdgQ9e2=~F|x&@BlcMfwO)VOzR1ZSl}H8_s&ADDEy*$0vPJ<<(R~qs?pdJi z&q9)mCS8V+azM1K6(z(cieSH(dV zmkDbDTJhCh=zdq?GIvp$jEqc0%ciwptZM0vs>Vsd`v?}f&4Z6;3T{fI(@I)V)84tl z0DS_-QUw}a4q@?L>o5;$_Y7h>rRRPe)$c%hnE#QslfzAqMvCz-9?H5^Y|TKL>CXsj z`xksZpL-MQbeN;%C@ZQ#iU4SP6z9updkVM|-=>B+pP&aGhY3Z1%7j=L6avm9LT9_5 z1Q5|kyfCgkAFk?6IxbPBv$W+&dg=1L$jul%#-bsxXd+1xDdOd=6bb+wl%M^ z`|XWlLKkhxQ2J|Pq1iz?>k|^8o5@c#?7!sg`}0)Xxx=>`@I}lyp2;0#Au|<1$pN~) z-R9A-echW3b%Vf4=tIvlc-`Oq@VZH)+IIzqR%%)n!E5)^j>7NkZiMWEzvHUx$RYQ$!8BHHn$aba3G~$<4M(5v#6rxmP=gcxe=Dy0hM>0du-(Y&OZR^D_`mP6j&~|?lqN< ze&tzw3>gPfV`5X&IE}DC^#qsuh+Que6q#Tu&3r^seatB9;`;m zhEHUCCmjcpvXT#o`$Xg;>~%a4C_*;6lf=eiWN7$QGoY0HZJj@zWGmb3JZ{P!3jO=_ z1jw>?cIU-B3R`PLI!OOAix01#el8Ri!un8{fWA?rPI#R5F}9EcI4?CN0(h|&)rj3D z52uy*Z2`z`RtsSNKw&v|*^5<0Ku@>2$!lGU`*8INyDi9;bC|67qaB#9is>8)K2)@p z=4vtiu;qkLxZSWOgnpdId6%8Y>)rT=OBeNw!~@PX~y()`$LoR6$|5yG$PV)KT$Bm=5Liw9Oi1o`4TVqQ`0bpPF-9a>MO;&9}}}^ev_4NhK8n&Csi@m zWR{7-+~aeZ@Kx_nON7#&Bis={kJVL61mNTIqsKgOo#N4(5-8N=3v^dv&PKhv_ARv> zgfk;xPI9%YS=U}lg@q727QP3{OQH0rvPzehv;s<;L>1t>U&35d7By`G+ajT7mjmMC zrlgaZiMJn@yf9Qqev=JWz-ddvk?JNQDxnqGfb%cg;?PG4j3+L-FwuB96o`LDPA&FRLp9)JtgnUUi7)0DYh)Q9hMP5^;K^Rp5a<4ji@QX0@+p6N_b{<+ zp?Dva3_d;qvXR=Phm1Zf^C?s9+V8o>izGPS@5X;3@`Uz4C-?_fn+Q5lRJpu7&XYjUV144qns6OfTU6&Z&*Mi+zkp1!D3iY>%zo|`284PuUQdDf-NRc8+!9Q63h1OO2s)hPGozL^_HN;wzI zbosf(!kch}h0+5Z;ZGK;;$!7tf~I9Ns)OoKddWL7p;Ofpb0*cQkMixG_gX76V`Ky} zLq9X<_h&!|VBYG8@5T=zkg#-6+>Z90`{@|Og-5*bo|J|{$Fn}lmYx^R*E{Qw~Dd8oum>4aa0<07g`cLwukm5bcxK}~saUU(}#9tvf-+Ep2 zPiCab4$xWeqn+r^o^85ux;%r#&!XN_{~-cRfd|A_k=(YMQUcy$W3MBclb?R$4V^k-x_V7z!I7L+O2UUJ z>Fyc4ud`u55kTw}mPjct?n^}9O@g8OYY`o7aWFoC={)i?$`w>e(sq_dtmV4Lt1eoU zrp`nd#*UB!gl~W?uIv8Q9==^QWnRB9n8Jj7D7?bQfb{~T6(L2Xyfivd8KgwiW`WiX(ARb4(xt)} zt*s&vr`Lo#Clfw};*MphN5^OI!WqOQd`Oda@CgZOe+r@SZC=-{y+Gj;ZZ#-qnO_$B zmLzUQimdo8k?(%xLXmjLcis+c?uAG0)!JECTS3&IOv9h<_z^IfxXI-HL*bgG2zbTC z1ecBZ!XO(|4tibuknm)|fYs|qM&2u8`d_|^#8B$P5QzN|(2y9qiHYplpVc;RJSWGt zd^iq2bp`J`99A6$CV5mH41~F6UZqzG!f5Wn6VmHJNtL6dluNjr>eLWaYqK-Q2r&^b5mZxa;-u&H$JYu2xO+15}tT?dJnMXPsyT43xgi4rzfbA zll#tAZts&09{vie%%j#m_s8S$;VIAp7`hB#2xI}x)Y{&KgO|@TyE<8%yd8`0By6ht z;oiTw-Bzn42TBV{-Y_+1ZjvFDwLj-EzNMq<7^^_gpM?1MkCecdmuC$wbG7=+Y%!^a;0kXM4!D zq0-Om(!u__nqTi1@Cr~bGih%-7;GKw-_YVg2AWXFg(*;`oWoOe>1U+X`BcJeH@3ch z%O#gu`{moZiFGZ9z6ZN61#pGpdDTf?7!MXwQp?X&Y!oTx?z|sp>987PKIep5uaS{L zJ2Jvr<6Z+-ctLHl4f&yxonS)daAuL=VWRf^x))d0%td}?3~U~ znAf;F3>vkkAxTE7w7%?BaxN||u}RZQ55#Z6@Ia#(xEXx3`MZNF0i2CRI3|MO^8+zZ z8;(=&rLWe8H5~@rXmZ0YzAxg%LH(F7C5rgOVv>`suUY|9e0D0-}SfYH;O` zai!eIzfr}?VX!YE-56#?F`3RsKg;S`Bq8BW)$dxbbz9;h(<3F1btF#c-|Iz0lO4jM{8eN+N2?~sU%b{y@atQQ<2Rj^faP>_4_nRY z(&A)>G0{+bJhPz5p`#2!#Z;LPa5e-G)m&3{&e#(e?U<{ns#Y}fE$T}oV=vgITXxpB z5o|~0B8+!slmImSsEnT{RQm`zbD{)x>vmr;dY_#4x~hak#Bcl32M*Z{3&pJuML3FQvOWD3VNmAi}PIu6M}$Tcsk|eW8tyy z{_<=YU)Gt%15z5Ubd`?6=7iQ7J8*Su2$W@~WcXzgA6GX`^FXrT{vra}5C)XnfJQUu zrEow90S7invTq~c08A+E*@tZia-e~?2-@(VRO$Z)U?Mc3ky}?$tbgWU_X9_>X|*<} z3*%w1K=I(=m zjrGC`-mVl4hNGZPQFTx73+qW=No7J~QCAT0$+%Wkl~5QI{+_uF57`Z@hpi*MR(oC9U zZow<~MO#|4_I&W_@+l|HFr0*-ZE*7e;tRJ8SmPP{hO}FfoqaCW%Taw;>43T#35u49 z)tJ~uAz9_603<{SG?Ll}5KbD5=)8Xxh{SE{l$SG?{rw9lv8V~bjzTyw(GJ+j0>B)g z%uqTK)J=XO{?f25jxjxMI!QY{0qoOR8UM1go9$Gqd_f!H9}XtU`&apXTL5Vu{Z^Hyl$m_yL&6ZEI|PJ)+3EYC z_-&}0=kLB`UQUV(>2$S~=vyu0fAr)V+Fg>Le8NU6MIHIJ4g}eMwqpjivk-~#pI|#d z(^MzhhqefYEdu;{;4?@+o{5V7l=K*c7H47cnKgpZn5Y+&j-XV`sSw-23RDR$0P_|C z!~Ebfgt(|`ueE~KUoI%z#*jHx>jHBD#>-@w*6v^yT~A-%w&UOLDjj_h2j_eyMQ%_M z(Sey2?qc3hs-Pcu2OBWPI$G2SgH}Rcl0OTA)m|HN(qt(6Y^g9}TO4U$Ad^LA-}E@gGfUuQtSHev7IrkgB}F<~UcQw#pnA}! z5DH2`5Op394g-+kcCm$2H3!As5ASLv#~p|Mhq$Q+`yOrllp;#_%*7vc$(y) zXahL-qiBx2(>itFf+MmXKg4sjWO+b!efxs}i$LyPC9^7{bxa{2sr6y}G5l0)^*hH{ zm;9r)*Hx4?Z34<0eJ#(dp8OJ=-#YOgXkj}TQ$v#k--~p-E8IMA?W%gKt8Gh;d`{H= zd6KrS<@mleOpJ&rp!_%(xMfrKBR-+0`@VN0&=|PY8c3>MUh3yHF#DKpZuHwRFMn>aD+zH1|arJu$~6_1_P7n0VYEUyIIJ= zz(vH-Sliq+lj@Bgs&o-jcli ztn3CT9mYMQXBfNJc)w1nC-HaUA~BFXd5qmg-Kvj1LXv!j{|1U8s|=c8vJp;-*Ns&d-} z)G!PU@}D|O1M}&Iv)H}7FfQI1ZZcbpCqIjaBqM=9g6w4-+u`olVK;Zro$gWtt)}S!n zVEi zfp?Kw+e4$j?ET&Wq5?XpbP}C2Zc0FHZkvL_#}Ms=8KNV6ok_<1FEgXaFtl;AND_#K zep3m6KmrC^=mLPb3Qk&3#m5ZCbeG-Rb zKZuhKR%n`CJ2BD4(^A%XApro;dM`}9YBqdJnTI3+_MVQN&NpkT-19*lyT0s`e<0Pr zwP`kTs(*ap^a)H?{h52mEP6)Zyy`00<@M_iSjWK>^uR^&%V`3?@MoIsW3A-?^mfjH z@81~kdl*QxbJ*RkRvq1LtxyZb0l^%#HEgWU0i_P2!$iHjpTz#ssZq1PB&2^TBdKJX>PxC|#it4Cb8goF ztxE6mxd}>O<>#gC^;Ra(kF*VF=iw!%8e9_sQDl|9KaqFow6+3TeUAD*e#sp={{C9bk#bK?_gP=eufI^;bueh`hp=19 zIcjU_0n#Z7#fF&jFvT&M01YV1p6y|7Vu1=1W z>vTtleQ_h3<+JgERTI~uJ%K1TKraMTluY)~^Y!s&RqYB+#g!@*Zc)6|gIN^c!t8nC z_!3T9%3xn#Our1Bj?-m-^*&fPueY8R@&fS{Zz|~Vb(9tz2BjQ?WgBR&RnZqXQ?1VU0|QbpdH^8?&3 z%tw2t)$XmY@7^M4-X0DGDbem=xFrfoKZgm9I&LFrbvEA#8kj0KO^|Aa7dS7eau3S@ ztxEj1;v{&V=_=1#&|RD=4k%-P1iy0qaB{{Eg|sWHZpzon((yKdqX7v?P&V{k6|0S) zpJ;f;b@bF8#H)hfyy12|+M=vFZW6^q^W-V_j>)4YU7)gSI=k?O{raf|!A|%=@0QS6 z8RA>nZ$;eSD8pTE;auZe9$@X2*2~ItSFE^12a3l$UUOc{wP>)e! z8uNvk8c;71GW*IFI#md2m(711Hol$_+=m@(s>W+ZMbBQuv8Zvh8u49#cDj8>4stePlT2Su1juwr8nB!qUh85%Dt$a_!h)x6xX$= zpeNIwXP{J5F#Ra;06FXHQ**M=OuwjdA7XFC!-IZFggVo_t!v9Z)v~jhJ>Y@_i0!W# zSj-2T4u44!@L0rFm<8+#qxYbS27N+Jz>1dS*P|68>*ZuiUoJ%|l7QV(W4Rgif1qzf zUcTTZuigkX6oX!W&~G>+@j8402XyK`{V=f&{dNHMAa!>~q|5AG>-%m(a0di#;t#DZ za>I*_h7=NDv3%$vdNKGUhx z)O_Wp4crB3*$lV-N6tH8fBypXkI5fK8-ToGwHrpx`zOBrw8C!AaGTHdWR52c2@?=C z{EvIYN7CccPTTo01!ZUc%#Dy>|g1DS|1Xm!_t1HK4s zRy$&lCjuksz(~;VwjQ*YHypjq1Z)w6NDy?T3!{zlGNt^qSM`CaH{1k+E#bxx!DlR& z1^2>VS6G|(P67Zpgb7m8_|G&vK}Y~M#uVC#g*wam0!UDJO^LQ}KJP(R63wC{^b*V)q6p$Q(W43?@P;w`pMWK1PVvbw1>uW#axsH3 zsURa2@?iH-ZOdt!9cbuvqXSVUq!7MAepB=^9WmogXdk@zGcZmvbl5`tFq+K(-XORK z35I4yjIk$COF>q^Z76KRB(xcWJQkcygoN%)-ID=%C?KdFVp@>rlZM4(l?=pVDf%V& z_*vLA3sfWlUbKZNn2Lrc97f!Pl)S025{>c2LXUJW`=clk`9N+3@c>Ix>z=5C84O^M z03K?T7|~2OK{p@=vMTzD0lr$IwL>4Dnzq?r1sKZ#^W!TVADxg2FpLNI?xn3)u>}R_ zae*^}OwHV_Vkf$ZJi3XoN3|n}@tSXnl=RmAAj#YNc5rwumI9-Ki)!1SCF3RG!cnl@^@TT5nAD@Ew zi(taXETZ}B#k8j2AZ_^>J@JE)$|)N?i*&Y_n_u=4*4o`1Ge@hU^JCwGDQ99~5y{@h z->J$$HPn<4u8wV*Zr(CrF;}x|-B9z76yq|q!h)hwg=sz}C2ir9zOCz>c!5H%6_(pw z5-c)1{8=gBRV_3&xBI{wWEQw9)PRG!0P+AFi`PNtcRhSJ=@XUo%a+PyqaT+3>T;+$ z=4WzF`x${3BSkyYTh8(h3(2cq_Vy_RZ5pYUaS2XZ+Y9Aa$Q-SPdf&N}11?*bj?_$n zD?TBeHh`;YE7gFjn{P!tRPmQxZh8|gRaBt;#N`bI9riaO^bOd|pIPb9UkX$U#)X7f zZ(mjS*%drS6WkpCwm6^C4Km9+AT*d2;_0gD%NjXCOom1QOELlkv7G}V${K!ixE0`5hI znCM?54x%=Sb`kHIAdxe4Z7k@Dkry!8&t_nJ)R{hi);Kc!5+uHzTK!`*J}IrloNBPh ztWTn^@G&`M=G@sFGwA;#>pkG9Zr}LvPm}7Alp?zn*@WzoL{TV3HmMZJ-s9+rC^K1Q zXO|H|cG)9T_B>_py&cZ~x{v4k`!BCoPp?Pk+@Jft?rUG~>-u0UbA2}tU>?`0y~(m@ zooCZ%XPsvQc50d3(l?S!V!Ew+v`j8BI@}lf@vPoi62pG0!L2?1Gx*oUVTR6i@K^22 zwYgV=e`MvegH|2@zpao?s&QUb(Q#m$Vw~$`@xl9vCd8S2syma}-O2{ers#^_x&2O~ zxZXP5(1NrzFlYEbb1tJ3@$3c97zdVy4UOVR`tZVY*gZC^!FjoY>YTs-FMg995hM&; z+F|93=~}fs6h?pr0wJfp%W%5P_5m@s<*3v~m+=)B`<0VN?G>qW#HhaaAjSFvyctaG z!(iPtzh&EPcYFe6pY-~V6M-VJ)-~^7ib1h!$6ylG^%MY5O+D`MmAT z`*p@=0`41~n@R&}6_Cz%TO)<_#vKNxBJ0OLUM~<%U+fGh-iAc} zE@J+Uo{sTje2m3EQ6)3WPGcpT1g+ZGsFi!bm)Enqw8!VB=(`JC)_%73g39U^)}@uC z{kw-3!!FR11XA5Ug;g?3&F9TPCVmdTv&2U+*IVi`+fAe2l`}nE4O`5K`3Lh5sQ$j= z3nb|kUtSJ~X6<)L;J4)epjPM14T2&@;z)_RjOQ4V;~&oI@uZXy(#1@+dkS*{WW<6M zZt|;@!d;o_8x8;d>*f-}*tg&tOF1(jrVHZS^oqO#F|^_=1S7HsPHt`uID-}{pqz1e zv=$}UB7<1uU<~Q!C^^7=)RUnwdD$MK8LJ zKrZoq;@UU8o4#SX9j*=UD70GkV`?S?LZ4US$;b+b1X-)9>-_N0QzCMEu)0vm3^T{) z_XQ4bySd#w61YakfU&q$dX?=f44|^!5~syHibfw@03YQ16WS+H<>R^Fuw!bP!HEg? zxZO?G-?8V!fT5lY0DFx6zRm5*eipitl+WH*%&!DJ_7%db;NiSm+&kXqt{9P z0rO4zxJO^=b7NB(fz_>1pL?gNnCqV&2eTA*4o6=-xN(bnAQrh)YAuNMf`Y>d3q*+p z8K}j$i1L8(a6KCRdR|j2@b)3$W8X?dG@p_PWOf9M;Y=)c$OXBEnpp!j z#88kM0IlH*Zw?3UgOq`S>Qzx3cwk$(Oy_y>7(m~txuC78U5yF@AM}8r=t(2acyt0L zw9H3+Dd_{FUm*0o-u5>QND!onex3SxLfUH#{rb=&OHR3rv|2+N%)=G6jmd`EK=YN_ zT7xU+zj>&Y_bAC}Yicz}I4Z#t&oyKP1kY(Dtz|%3E6!TRO~hWi0@7HY(($xdT+g|B zb^vX>wvK+SX69K8O6BryZ(I_}$>HR62f)FHgw-i3-<&9Dh)M^%A+@h&I>4qK&hzD3 zwH~yX1eNTCB+ldG$ianQ5N0}?$fx`Hxa36d$Kn8L771aSAK3J}zfjicn&NH@2nB`< zbC=}`JB1l;>L{AH$h(T>9oZ}Vf5&`n3FpLuKv&tkK6s>=O}0r8Cm5W1)+YynL%>DJQh(23%a?V0+rI9?yk?mRD0n7Jxo;L^75LGu7H;42bg&0YpO@Qb6JrvP{W)= z$IH8SJwj!rng13(#CBc!7WXL*5A z=j)%J8&pLg#1ZI4fqVK3K_~W6Wgsv*BR^#tB~hUzjg&;)i?wBML6~;>K71mT?|SyV zAI_k=9rs+88v*3U03B5)RPNQHp`Y~wza%7>Wiuf2|KItB?v)$_Gqz|W2mVFd8`w-Q z>tHaH0f1z2tB^}@GG{{T#sT;Yx&5licL#Qp;Bf12XU<`=O-j)H;9GriH=Tb$J=D7s z_$o+*M2IUuh*{L|c2~YHXoVYY<$CbGH@k@0$nwQZhuJ3QDCgj{&%m=is7KI4JRf}M z3@WS3^3&+rSmuI<<9)uOoF_yohv6O=NgMGmk!cU@GI2YhqS`5?cBQc;+s z1tfw$`Z%&c(C6_n{2V0|R1P=*qTL!m>o8Y>6er!S+iKO#vn`qHI_!NHq_dAQ``iU{sv&_c?NQ@VOuG*KZpG$hxap z2*?eLh$X{y=LrPtmQJj8YrCvdP zp43_1S3ZoV1NUMfI>D0E*B5)71F0rg>_E4Mz*s^EB*j!NmG9O%|95Q-B>AA`)drc{ zNmn#_RMLD9#-QBmh8^7K1$NtF9bAM`AB11|KKDXKB(ZN_X8e5e5X(icu)ro}ED`_S zcx&uR35sc@+2v=U{ zg|W`vBb~Z7ecfC%Ch+z7vz^jwxpTO=iLJ7{hl%BUXU{fkyDP}clbcAC7hvtS*zGByzNczaJ2a=4~G2@i8)6*r!ZfiqduiF$;Lcr zidG9_-H0ybx@&6&QQQi&4k5T+P$^2m)V|eFUB}{%j)+~eoSsQNj!$(gZ#^EjN%23A z-(yjHG>u$w=!@qqC-)h;zbjlYdIAMBL9Zn7ZFW}*hG~uZw&-<6o2Bg9b$BHBYS8bapFB-|Lcy$9G+Hm{r!tO-zRC6T&n@w<7no4tegcD>XZEW#4uS!Ek9* zYRv-1%KEmMg#?Xtex_R45YAk^op8O0R(e?K$<9+R4{pYO-3nOID<^b67vg*B4;O05tpaM0 z<*w7wb5V32Rhw-=^1p=)W(q^3Wl*l}w(0D3)cGUNl9n^_4rhbW}3jXyuUe0tpUAR}Uz0|5XwdFSYTK*~5!PUCoy^vvYd?C}t{+vSs@u_=Q&cfzml>E0Yy zGcv6{=fgKh>2l1Djr~l;-vKwnE!H`_^%QQ~qC*r@W4F$Y`Fqb)7*!_%kh+%TTqICy zWiXgUwjMM3;Gif!-ABml${i`&f)kVBEGu5)MbA&gV{tz+{e2u~P4L8l)-^XXW&IAp z8`WBkEytjpTsHdp>+1Ue?!eT@_8;p0_#E1*2Ffiry0h-B7Ml$StR+ID%K_7h|C5!N z?9MAyo#`r@ipe52emAjyB&B?{T`uC!3J+L}NW|!IFWVpc@Xz*><;yJY#JUZZ63r(X z@PsBH-=k3Bqu6j;-W4gmEeE$PdSc2{xQs;53jdSOHHcm>NFlkXYT(0!8e`AO((>$w zvwh(uJHOl6%XcWUj>QCkEUYw72MTAGGS!7z zk(uI0sE)4fj8@n3iP^O?6TTnfavusw_eKLhWKI8HBx$^cGw4{l<0bj>kp9?S?AtGZ zC19BFhh`)lOkFTkaI!g|)Fr=f?R9vjb0agi?&|AqEy@Gf3EkeUwtyK4;tGz~DBC%Z zZj#0cT8=gR7U+3?F_K4iD~3+lo7U*|oXl)gC|CIQ?0XRrK5^+Ot++|BNt}~C11a`T z@!O>o^u^3LTmC7dk9ztQ`?Ku!V1J-j6}*{{$S0$7*G+e}Y8VzW+9 zi;R4rj~S$YEe;v&#RQ=O3hgKKr0SI7=KOm3PQiDP2$F#2$9nbte-?qvw1?n;e*uK%;pEjum-*a&~Fu< zizETed5E~>;YdVJ!cwxF)1BVP!{AXh8ZTGvH`-hH=;1y)EEj3ivmfCKpwM2< zbLy}O3c<|tYRIYDH|7kOoTM%lmb`>g#2pcm=x8{VzR{{@ujpIn4U{aULiGkw1x>Lp zid7%DO`hKtJ@Z^VNAP+u?gI7U*qz<}L?fk;0opI$g9{Cl1hPn|6h#iQEa68gA@g#`3N(;ZZTIj> zjhXz0MVa%9ILSq5l!Nv(Cnvv{2uo=BM^(|bbhvnGUuNxH2(nV4Q`0S`5%;FQb^;jY zXWHNlbg9!8vnX;_kCQazkf$wx00QbrCQuWBCioMX&DKmFu#NvueTefR0e>Uw@}oz< z8hPtM1w#3t+1)*6YSJ3{jv{7;}Vj2{F^!uS7I6#FlFiTL7l^P{VV=9GUM55xT2Idxi=~wolHn!yEi7w2H(F8HO8~j zsACRV`)-?;XmA8hlxaZFGenNU{1H@rF|3)KdGslAYvhc4M4zYK(N6iQ9Bz~NGVECRiqIB{Kb4 zPq_E7_>!pivPtB}Q#nXnnjB321N*24maK9F*6VK#udG;mq8*}6e2kyfsr0*ZV&tc1 zHL%q)I>0%;#zHr~vXN@lP|;$!OR9{yWvi_({s;Sc(J42gX0}W8cPL@QZ|+o@O}8)z zt9%QGeyJi-)KeiCR3r%B4t}#noq{aD%bapmTAt^+IOdy;ZS*e*^ zzj;@r$3(>^NCp<*W!_rp0A7J{6c;|7+mQP|*aPb1mZ_w7jV=Io0jdKhLM)=JZ;`4X zFIm=f=$GJm`BaJ%gPt(tVi3MAPJTQB<_0{H@6+O@E+hO`xKv~M;JGNe?I)PaWCRVB z81{oi$tU&3L2BHmh7MUIwnWgzUxI#n-oPtX6|cEX&Pe>bKl!SsnuzBi!Pd4m>XayZ z=MLi=zA(?n1DZ#H20Tvx9ABMt<2`C?_fSgV*&(V)Z_#*nn7(k4N>1+t+YS6H_E-iU zo6$#73iYH-1AGwk2p$no@bT$dsTvZP_RkN7Z}r}b`pl`Y&#T~(*b!)X{F5qAeuG6R zBF1TnrfNYs{Qvj$YqSguekrki?^b9FSrrUF00&hI(6Q+<4SK#mckRys)PW1*Z7=yA zi}2%*7lPpF%aGlB6lYELU zS;^;{Ef6r%ZspJ-G0jVgX=p(MH#sjL+&dGJt&FhlgQ=Sn2?) zqRl5iRwr?*;sWU@(AEKGJQsNRUptC~D)P2qL`ZbR(^Sxyo4g963a&w7gbE+v6MOHw zY{thmep0Pv5?V+g^@v1ZZi>#6yzK>|4R8{mm)`uVPMv%`DCkZ0$`P2m^t#&rzbQ5U z3borr7@C7`k(aq!PQDG)c_byr1`E91O)ZXQ8$d(Vd+%4}yedxIqG4NSug_jT>&|e! zGBDa*w$$b6R(_HH@lEF~>(d}d-|modwZ;uY6XYvJnV0=AMYh`!bnNFsw7?y`zwrH9 zu*=!|F7gCN#6p5Ghd*jdy*!k{tHT7Gtrd9dVhSw6f0ASg*;ZCoA4|B@*~3+bJiIgb<@qI82rBiRG-q zm6umfo=z|GuQ^C1kgt6P+VK+Ot)@t@md3vx6KNyDM^VW~?Gy6Eza=g@ipynWnjK@6 zHIKAxkgGaU>GcX1kUIa`=cCjaBUi7Ac;e0z`DtHKYC3s&(SB@Fk>}+h(gMCDHOLuw zSuP{P?ATe%Tf%JPG~lqCsHl#F$8LXcHiQhw$w=){Kcb1Xr-i^ov7Xo8zZXs&;oIDb zVb5oyqN3p85pbB`P%L`GzjL+zT&Ldwlc*)HuoL==>r~QTq+VCk#M}!yw}qf+xE!%P zHSM?mW7awpzL+Xyq@(AmTR}X|w^_LJZB>!exhd0NCq1#ws81cg-Ki>*@76oIsJg!` zS6h2%m(ed6n0V~Lg5FEU1XzB~5;^QeBhwuzavv%nX^5BKJ8s|M%6hm5GbGi_g%h$0 z_@<~HC2BlN-iJMiKc%lcvhXEK^5qXm)u5EGY*XD3MW0X4SEr+x8qXr3h;!~a3b_%! z?wjxM0!K;-lU3vx{U~IAIkUc-=o_>`MDqaAuFbPV>SkDHgKIl=og`Pd0xv_z zKY?_W+KEN$p-X`x)d1k+Rn012Jk^6DV5FoSpG!*jw*epdCYUeTvNB+C9mD7U$wT@^ z8+!9FmbH)D962R@go9WrnUkY=Sa@qWTZ3^IAQ4AUC{>py7q6Bl@^r~EmmZ7Lzq>T` z#gy_H9Qh;K*08p4EjhUQ1*R0&P^mgjV>g-G&Kg*ouF>0S-0paV9{8CaN8!-1D0neu zIOv62ser}KzknMDkIM?>QVZ|ioTB@iL_eb2X^2w%p&HGdkw{X56p;qAPKZLpNQ~D#lTKRd z4O(ir=0+!IM)N3_wY-p)FZzm4s z?*10tTF{YxJ-zd8WhC&HNc4XvWrt^bh=&vyt9yHU8(UghD#dciW2XJN#j)K8(kN9c z^c1?_JWN-*R?XD|j>9b;Kuq`&?e0!#8d6QLwx+t?P*80ih0~D_KpSRK6uJVR4cxRk z16#?v4+%hcDFMd9ht!&y$>OT*?_V9lH&!?WcG!CFip>d{7?<6$+AmCJ-hr|97 zGSlcV1}$+5$>gLwQ>;SI*C$t?9TffW!@xrHw+BOm@wdoYHK;32ph#i&hctOKb)S># zVU9pm7kDOQetp2ozz<8xBJJX+K*T}J&>0B<>1THwXR5f9YXcAgR;58sZ<}asJe2*- z8;yTXjX{lb^Cu~m0Gp{la1 z|KblD0DRyh^#)Hz5h_2J7(UciMA`(?CNb=eZaLR zDUEWkx2Jp6&irr=INf!eY70g-%0DI5sbA(|4C({!yz_$aRC5yLB1-xl{VbQLA_~FH z+HF99aOGLw378&N6+O5=j&7q6$ZTqe*y^2iD^&z)HEsl-qd>7r^X%Z{G1j0MU)B#W zcLU7#K=1-LY*#Im#AH__4;*OoCAn{#wwpS+(feZxSkLmJI;b)X6Z32AZ6R|98pC{f z;3|wo6Ct=2s#alUfL_?uDpiy!sCPc*QPQ9zy9WYQlFIjEkMp?gU)o(Pmi{Qt*$!29 z-vjI(9!fzX;BZA(JvrkUg}6;Ue8;cu82GonhLF`@gGZ!N1&ACl)q;%3BCXWvJ&S{t zK*ewqDa4=;cA=k=83#hf^DQs#-LTO?Xwr0VXuFIT{_nytwRTee0ulf*`;v`r$pc*V z7)-L=yAKOGkM5sho|;N+2(V6A#Pd(J8Ue7dEPAIM79_6vWRJSAy?8}V`k2S*qVoWH zT$Hzjo0ixGTwnnoq&^*CmdO$ei0zGPAK}O?i+|HqST53TcGTA4>d^EkOsps@%1Fp{ zLk?5gQH=i)=Yi4$vdY#+WMgu5oQ&*0m{TE)}igTn5g%f7_~;=v4HCL^2wK zb4uOzEmZB4RqQKXWz&i23uj=U%dE32vY+wUSIiXXR2xgJ-0XN&9!B_D>0ISSGH@4K zurS$=>1LSH=a0W>MBVjm(xs=)d*SbueKBfIuOa_LVKxw4*p&U?nN8(u^#FL4&&{ee z`)LkB@2V6JsfZ4D|IG7>jx3l@i4Sqs2d=hPQ_>MZT>Ca+t!< zB@EBX)7GlDaPKZmIi*ofI8R~oNci=!$*!qz9&^X-oTP7Lo! z;sVQ2ATq^n|IHeFuIHk>v$=4RLh<+3v|#r77eRF$8PLaAdqoon?CqhtyDVlYyfHL$ zMeBXA0^qCS4>!GQr^T&CX89m;h_+{O`2ABmtLQHN#E*YRY>0~iixA&)36tGHe2b+X z84{>~5!hORa-my8oh97wltR!6RJWJC)n8L=7O#aH3wfNTA_rEwgdAk+hE_RDon0aB z4vz3X{5;hyLcxqnFsmEkF&AAx6#}F|ix zm+$zS53g3f@%v{v+(yXbNn`Jn^%>Yu+3tp(gqIP9E7E)+6>v~Y$V9_fce^JX#(yQH zKNjtq|064=2qN#Hi+s4@pcGFmd34>WX<=(DX41qUd8X~E&5%eKpMR#F#Qil^8UG4+ z4+|@3LfL0uIRNTXJu-9eUYxzI{cM_7x(N%>eQtz3wB*B{xc4J7D}^ldFc*L%u5F28 zx$g&88pAdV!=G?b9|i}CL7Ap0urqdTF(!Qs7W622LP~C8sh**HQkk?=*E?+P`05qg zS7)-vy0V=eRFnbOQz7aqS|x_x|MfD7wP}u8W=rRN@#4k8w2ezb{Fzs8 zRmC~nhx&3A%GQ1+Xa%AdEEXa^v+i99qvrd9A;afA*@GeH?dZ=*F3wky;g&163Zxh7 zDsKi#66z+(U5DQ+eEySI=`NET9%Zc*<+j=_(JVa{HLF>^Dy(d<)YGZ5VYc)!B}HU) zwwK1MV!S4BXJ^N8+lkMBx&S9QRF5^7pi<&i_g?5ZL0SP*d#j&qYt)}^Ha5dMUj4}9Sm97@0yOa?34myG6R&1l(8OfIR2 zjf7b1CUZh}L|3te!SeEQ*`K*J2fONe_GoI880-61Q7RQtbMhA}{gumON2+o!`goqgg&G>@r}z zp|hr+RXml*%=-@ntirI+JaUV3{E{Roe8G=yjRUZkaj=U5}n z8pP@(al8G*4OtBp9Z8WXD$eBMVu>>QF+IwRtudVR96FzgR7>D&Ic|dVAF?rG;QEV3 z{N_*Qoh@8!vHFS4&7(EBEmCWQ*Dvd($Et=-`6r5=lC36XMUvW^7DC}!K_>nE{R{Ph zZiMf6+)(7;3+DB2PO39Kp)1$;ezvxrh$W8Mjp?l>}|SaGoivfK;^$RhcO<0sGXWvdVFB6(^8L%%Hm-mLG^Yn3K83aFoeu{qGB6 zXAkl7SQtIt#vby*m2Qhe%re9^{CaX1x`}j?cd6y&GWODiTnEX>lsAj6+Pr^z*nfY} z=`6r3q@Dv?172mks{8a1W!X{#PGn4R4PP!arS<4T3cTBJadUNKZd0{$F7;(AWCQ13 zr^I%<{Xp7H@>9JVwTIsbPaDKk4(>sqwI?0Yr4-f()VldMu%`FiTV8-r<*>b8wQ^unah!-!$in zrrwm7l({*ns;X9J&9M{&-eACRg4`SzYccpWnpwW z0#W0n*2o;V$!eOCdI!{sNH?6-ztW!Dxa}4h8L4>Xg_rM#!X&X%+`2*|Su;~J{@bF{n8}Xg%=nwY}*BtBBqYK z$5iW>9T*NV5+Q`jK_I-sVtW%?8= zxW)_nFQ&DQs1v#TQt(G#YCB#rS=H9|L5QwRP90vU~-b zoj3d{J*}@EYLQ;kmE7vHxpjg1(XtyH-D43M1WdL;nplW)f1E5(VWk`pcrwfVW|Vu) z>4!2D@zg+y!6kOKA60zJP7j)kcUo6ml9%!-D=SI&o|59AAc(a|JcoE=gyfao4>)rm zRVwn*v%a10l&*gO>oYK=Pu%R!uy7p;s3ewUr*Y`JH**c8+ceh;$w#DSXA7u^&3qBH zsBSnN{d+!PYtF!V$zMeJc0=d#3ZtK%s+9TFeX@*;OUGfF&Tb7UCV8)Dz9N(R`k$t` zGOLYj={cFa0+}zfz6PQTL$RB~Ia~t^0b}?l%rYm97J|>8jJ7F4mpYblPb{JJc$s~t zX3Nf`p2JNJrLJNJgXw|X+SkZGO1%x97XW51J2*J>xemF2@R|H>(fVp>_GFc-MM^~9xo5(vLu^dm*w~nJskw?HCHmA@6wY1flJL!`DVcRVv9=p* z&HVRzY5fb-gA*n(ulDu#x5iLGJ31YJWf5$|gL7p4mPgMbD7oo)5--(Dms$R;xVM(X zx4OMKrSC9URc-*B>$=&dQ2BVgm14o~vhmKE7yo$7NZK0Csz~h-E zV*5^RZ|@Uigun$$0@c@YEA8}<_C(T5Dum+gtztNaz0NP}+ma_F2--U!%hukarPu7JP&4sZF~LXoMSB?-o5&yiRy?8kB+^w z?v@FzDDP=yQX=pU;-!S_w6x(Yw-$r#_88z7MmIMyF8Fl zeZooFLmqTz#zD#IC&|1Ad8xLW!PDIO;r!Y-QW)Z8R_sn5(8!o_WqCPDq`OvT-hsKV z6dacm%G+g{x(loLp4_o+qD@QbT3KO8))a*BWiXI$oY|*rV1UN01k~6g5s}&oFW>vK zB~Gp4zy3T%3~Lg#ve>nH?}^)Y8Q1knKH{*6w0egYjF5t^l&Y-q(L8~RlEEt%YTJJP zDU^V)4(2yvsTXN7zp@;)g$YD{9Pi2vjnL*Ykb^Zwbm~tOkei~%e;w*HSSxziy1j#2 zH6boExy1A@CBza5G+EL;V|L(cFR-(Se3hWQe^4pKkZgm z-0aFNcBtJaQzXOWKK|X&er?vchFmcRH#g9=+Lf>{G>7AhaUEQsJyL?OjyDgkb#eTO?^0tIVBq2AB6?XF2!z*wX$#BLu`@20G%vfo_0@It&|fJYMJo) z8R>Y3i!HMQjFd9VfBX_W!(;5Vug8`@seCz7T3XsKSabo(YmGfG!GImd5C z$kDocjxUAv%Mb7x$g#WNkm!+oh-IQ$=Js2n+8ZLP^RH@}=#}T?TYnt57D@vXvkDw) zZdHI{Q<6UacZ;}cA(8BM8B+>_1S2cT=G{TPDYBtoEk_Or{KUhE74_d;A%XP4m{wPb z(a@E*ZqrDp4RHNaD(P)`NL`fMRZ9$H$KS>iEk}HgD?tMz8GdWvP-_`2)*2j}N3lU( z0!{`h>&GckD=cPb!kY{^+!w!v?eb&kRHh*NR#z{6Apl$y>kVdRLTq?4<9W%=`O4Ov z%>zehszF006Eb^Y^gmIcfER3vi4k^9#5yaqp3t{#Z5t&zfb*c|KLeJrClG zi?>pz=rX@9GL9t))cT9yZ6}Z+$@`tLC95g9Q8fe$pHShR`RPN3Tg{C|TRq>{+Vir+ za{v;?C`qVx{vg@G93~^B#YJ0c*;BK`zmx^4tJ#_{Fatu_VDtB#(R;{PfW3MuxzeVt zUZ^i$mB}9C^Zdz@q06w}0$ilfCZOLJkF!xyAdh=DU3J%RBrC&54q7m2Yai(C z`}S*l+*@WkdfFJ7?tCE=_xH~R$1cslWU8Yz#qJE2 z%)@82D2ppc>D;^Ln8%*(frgjAe_bW3--f4rz;Yl23%pU}61Q^GLXx#f>+D(mjRwtT z9c1vzM%D)4JsNYTxV5R-xupbPT;%%Wr%zqKkImtWMOJ6rcw_oYU9>x=q<@}tD=ifO zzswl7XcVB6bFQekD0#WCx4_(Nd}d}QM#N&^-(bG|-@XurpYvF)HtI96vbL9-X7b%JbES=Avzf76;7OhM?(IbZdT{$i){122em=Gge zwEzA(6lQI;d5|2J2h3(}L-e?JqukyuTPHOM9XxY5Vpj5IGI4rzbga_rwp6i;gWo^l zJIhbgQaGRDi-ehlnPn;733D-Dmec>&;=dYhUDv#tbj(0~W2+jbH8DFY&EH+C?=)NZ zF4n>gCUrP=SJUV%J8~GxI4X0xG~wXGc6P2K3kYI%`sx8 zA~W>k@v~>V6XM`}D{T_2l61$u$L=hDd7=j+&EM$_mLJkWh37axP5>!vffNE4gEy|^ zlK3p!&cT5OM2*W}qoMFgv$YUzBa?oVPbdFrLoB|lix$Bmu6K(56z*qNM86R@7PU?f|G&A<)?CEjXtuKcXd86b3y{sQT3; zr}9CKwzJYKFDa3N}V+@*$S7hn*LK4K+vjBR4M z%vzrfyWU7p=m{0kGtZn`{Lf!KbcBYNbAk?dF)84r&DhOSfvz(1NEbTnbbV9L%QL8K z{D6mf%nU>z?ue%Du`6OPDd@0x-wW5-Ab6SQvMGPu^ zjf)EnRDkRE_ZuGar-O@oG`a;k?-gKq*Hj2wI+WY}%Bm7l$lvC0+y0%TY&`M%ggZ5r zKc&q2p9Y^UiJfe(BQ(-W4K^*?^>4~D3*o&zd`0VnLxGEKW2K|*S<(xE#C5#Ib_#B@ z@0~i`LF~S*c_o*@&g+kq>9w7g$kX>=IVhT{tFv7*OKB=P=<#%>JC}WRx_fET$A{T{ z&V`Cfna$Pl`dC5PN&~A~KbWigOQraC4d<)Kv5=?sHa6{Khp4E$-n>ay1ZT!km<%!;y<%@m$e)Zqg4*J>Gr@LrZRDATthE0nEk-$N0 zq4#Krkn$($#CpAz{bT#K0nTQ10}gQ~_JHrHu;mS~cx^A>y=gCEoNU#in+x9%;=TH z^4iL3v#8QIM852?jwOj%91ruV{&v3qctTY?O|n)7A*jG0{lqix8YGq@$nOcEpd2&S zyP_Xszc=+%N|bfO;B9G~rD5E#8TY*}7wG8e!F8!EFz1@^-+85=pl}~ti!g#63Ie}m zc6Rm(j{6_b(bxcz0ZQ$s#pZJUdJaWUkCtT3`kKVoHY4Y4@G_h$4e_p~=B_OVu0 zE{s=}`c?+R)jxb|ewaI-BFL8VP|+x`4{II z*9Sipv*yvt;qd)%;Z~bk)ZZTuD0BQo^UqnY|6}r!;EFMyZ7G>c*iWAHZf?sZpp*J$ zo3nU@Qs=#Yjvlq|v}MI^=lw=S;0}GW;ZGPgg&1(EcORv+<3bXR0b$)*Ujmnx&k~O_ zWZ5kEr)_!X-NZ!1yO;p;UI%&Nw=l}62Wq<9HH7xUuaXkXmC8w{{hO?v;IZ@k`Fl;) zHf0k{&88Gq^uUrz&Q}JPz`YtXEuzBgesP-7&wj}#hsICDxWc!eJ!ieasy#Nr=J9A5 z_Ibt4&8^XW`^U0v(^`?knx*>H2duG0S);8~8k_janC$FPV#g7~7u{{$-Q!fVsoEJe zRb7q=5NLL(Azn30yu&T*>?whgcq>fZ1#=lAW%dx3ZhXqi(0@EP?z6>2u)R6gWIs1= zxlH*_8)4_2ZzJV#XJ;2<+o#iI?=23>>e+tzcIXh*uj45ld$4p;OJy{`zv)v^v(j{5o>{v<1<;jRb6#+92r}-l(WdN_y&jZLbSh)7e7dEt zZMqEM1U(EH0U*I@fNIU{Bd&iQ>g|(_!HYXuPATcj2ud+7X^v^wwZJ`h2@0Iv);XwQ z7cKF`!Xl7t&96qPcvi37jx$s#O3KFh>YNkd6}!G(`^`P6T&UW!eiz-i_@_Hz)?md(+R4(f?0sa-{~V>D$k-gk z+U|ZzH-8*z37V=M8K%j{b5##Qlp68={TD#*54%kM`A(+ctW+T})?5QVwl#4zAmFP> zXQ{x>JHz{DT-;@THYU(@h zw^TitZ14iLQI$UJPdcI2QNu$sPthJ-uIrPBz-E^S7E~+y!5A5sr_S zwo=)5nw-UQ%zM6Yy!Q142F(u(3%ftJp7?eU4oMoNVE5$<3KtYK8aWQZ>=Kn|*9?^t z{i0$>W96IUsn({8*0yo8!2ZAsMK$C!&8pQumX}}S$87g|bo>S}|JdF^UbhF+hDp9y zT)_M7v^W5JVv{qfJIiJ?8k;d2g@vNqH4U9~Lb<^HqAr{8<+bJbD_KW@`t3&Nu*pQY z-Y;^pN3oxiNOJ5h3S1iaA1Rz4;LGA$q*l9hxZLpY;G$Q@O}9&3T`l=zBpod^85Q=% zHD5CCX+v7#>sMMAb~bvcgV?tsQabakb>T*AK9WFlLVfJ^1pC(JrUs#G<=FZ3(Y5*M zzm+M@E-qVd755raeEHGy@^v0WJu9f`H}&o9>@HZc4sIh42_0_H1m~O_wl+YJEC2nk zL4>ZT%v~G5`C)a{ZC9jGhTmZKNTDvgegnSl`zm`ORpS#<2}Q*&bW(f2yh6-@+vA+VSzAM@Q#jbaSRR{QN}#)aYSH%4(1$-CvS<*qWV| z@QW3DdJRuljdfUCS!rJ$P%30dQ7JoR5hd9j!o`r>9PN8TF|Z0SUrWL>8atUeF#wPg*GOxV=nkoeY22bR8~%_w;9|f zs*%)M<@D&ii}u&lcNQ2BbFjbLxv@PKBe4UzD^`W>hzHwG*sk`&^N>d7LSTt=TztaB zR$;wJk=mAkl0HO*bTTH_&s&i&^5V#+LWLyV0Egz?^&Tas&|BZH2<`3`bsBVx65r6K z*4%j5{8m+JWvMpS@xIU#A?&?8m*>xRQ(-pdn8!%TOa%iovuJUpn?3eQ3Bfvw6<25I zHybp|Ve(^^Isn3#=~D*BmHBGATT`ZXLQIlwzdACOG8h`J@2Adg;0r8&*I)^07}teH zgEAQ-N$kBJVlMi~>hBo#3Y4yPC-yDpN3(u_+twOxb1l|ocHNIPzPVM_G6-TV(R4B*ywEyt_Kqn zGyZ(;6Uz7Zdr%De3#J$^w^CLQu1xtejpTm}RZ4(x$C8NVaVk_Q^AmBvJ)L~yJA1)1WS zpMSf#SEcq8oYsVr*?s2M_LfZlxEA&}syQ<=*`QY~ErebQAe%+M7nw~lOz1`FiMO|O zb-^w=ASK>Y=xirFP|9CA2wobJNIb!}{4uoHmf4noC*xFxF;lx&_6>i3a7{GlB+$ z#qhZ~@Hs4&B~QOr4mA*RKIoy*anX#P4MFDWNXOg@X28eiLa35}n-yEbNZ(M53uxO| zDc7&Wi7Vc`ge+#lpG_I!xMH!oMbP7x@o_?Hi{#SmcvqJjRW`4jXXI<;k)D8J?2lW< z=luAS|Jq<48c4fd`+SGPM2YU1{x~pFe-*dQ;Z6dLPwWA7kDg|4rQ3 zD#tyJS4*9e3ZFt(B^cFfXpb8|tJrXNuZVD#Tobk9g59=)rp>j(F?bMycfgt8x>l}4bk|GL)=#vh{ge)Q5=Wa{faa^7MyWUBo?>JM%mGy-g-kP9pq7tiO@OyjV`*&JK zdWl?Nm4kdWyvs9srr6`;#bxwIuHNRzEH0s{7_Gx z+zJ+4~OL?qp4$va&=5BxPnI_IvC{SEb7<;tWh>2k$$=J|BKd zsVdY?bBh@~8$;HjvO57&%Aw-}cVb!0>{qRIqhqrg^KzHLQwt36Ux7bv!{z0tx%&t$ zP@UEpICAvaByKLYcuL~Q($w^{UvqPFM44n~F9=1)3ypidKM(&E1Dil{laV*rG&M$( zrBUnfOj%DyjW-;)`NkDZp$CPhxrLkqG(IPl%N+KtcC<0wH1>}_@*swl;^M-Qnprv4&@PfewoZRp?>!)SGs`P<_+>dgnroOtg6Up!)Gl{pi57 zr8(_ipP%O6a)Pt44}Icrpr!U&yeZiJYOdt zJcP`$j7r^}L;I=A5DzcjB&U*y5O`ow# zx{X{8!;{G65Wa9Sa%=q=C?Dx@9HDW_Dy5ww={84lb2!ZQpSBH>{dmd znU~{Qg>6V<6K?O(m0ukltI$dhT9I;0U)1U&-_)kwcD^*`8UhFX*>_nSlNB_Zm6_Os z3B_wTiYK3pxw!Y9nS}vI3C(#|e({JxTaHJ(daq6MdgAIIe}VITb$L9$PoQFnk5QF} zT-;?dtUzSH;l9b9lEPoCeI37l-~L}D#Dma0pXHj|NpVoY>fBiJpf7&?ljzQ9;Tp5u z^u+9wO?JVw*o=Mqtk!-S+S=RKERTFz2rb`?te&Qg&nRUrDwvI^FJb%U{5v~s zHHQ))T<2dM!M+`yj*jpf9K4@U`;`aOhTZVB(dyCUf!7nA2Cp{c&g{%*?Icf05a(5M zy{hjoFWc7QzM7akWu!gE_LKz@Zz4Mmc;_M98gct=IIqmsOnHE@MT|1;MuE#zfRE2m zcjtk7eEQPP=X!c2=%i}QA&DVzgA9AD(X^c+iFvSrGW_;lJlN`uX%d5=MG0N?Mj<6( z6Hmm4=gSa(FNm(w2mX*=c=v1OMeo7;jbS@q?K6&b9`*uTbGjhqm94FYRoE6CD- zB@xR6P)V?$AVO(|NCUwNWeZ7Jbc9elG6_mUi%=2DVwoV!ND?Y*p&}Ttqn1rVDw2St z0gPdrkcBPjy)gEV=)C*oy${Jp?h z^)J}GywIs%`co+QDQu6vkgrj@-h9#|PA3J22wX~kwtB~-zP8rsGv6cR*}4I+_s<97 z_Q~a}Vek&5OS-=+W~c9ns<1BS@O8oj;}}{(Ro#UDf8d5zIbm!#xmUv33sC{gFOB%H`yy zoR@L4beg$EkIYnc{n%lQjzI7=+%C0dR#hv`wVO!--HVJlGaQZKeG(I zJjSNef2qE%6>ZR>3sEge$&0-ChlVf$_?AJ`2sRm4?t2#K3lTamUxO%6OiKLRdyClT+uByKerEE5jno2F4qx9IYX=M?5NzU)i+L}#c^I_+ zeQCES>ao}6nj0%qtr>rJXIoRI>|_hj+FLy1`Pu}FL_%du-aD=HmYxopp)e(2JJ z=HH&c*~JK`yze4*(Ih2QtqvoQslmZiXf$_<*j zDn&BOi6XAEa6A@rHeXI!xc@8&j2WX#aX~`~enx5ww!8ytRVG~y` z(dFlZ%0lMn?U&cOtCQgJ?lgRTeL7BA8y^lV$8h{au}u#u?c&U3vkw{#8UaEK=xF~? zR(FTNG6lPP*kX@jUkA`G2LWY9%U@)l;=++M3rR;H11= zUX5c(Z|=n=Xu-D1cNySO*)EQiK>XX~B=l6a%g9zLGQ3BAiV#2uAOsKs2myouLI5Fv z5I_hZ1P}rU0fYcT03m=7KnNfN5CRARguwrnfY~8Htg+gdaMi#~fzQdIfx_dl-~S7_ CE0To( literal 0 HcmV?d00001 diff --git a/src/qt/tello_png/return.png b/src/qt/tello_png/return.png new file mode 100644 index 0000000000000000000000000000000000000000..55d770be6ad1c916d51b4bd69914831d71369447 GIT binary patch literal 20994 zcmZr&WmJ_-+XbXUj&w5~42_xHzI9Aqsx zH#2j^zV_Z@w3>=61}YIM3=9m0yquH<_F^;IksZa|ZL z9u9#P20@ZV%?wWM|M{l>l#SubYh;S@5T`Z77Jfb`dH4r4I5_X+C6C~rUWJ4VLIxX@szy(1vQN?&AvU21?mu*6QG#BMCx zeBw#vaE<9A3;Vs3et7TsI<(k?uzc(26wU}N z_E2%W--<~xoOeOL}^qQ}md1?A1T7G*7fT)q3;J zhikBhhKBZe>#o2N=9`tRm=jvz6wnU|ld4kVpf=&-;x_5(r0lolF3+UD3$hn1QFZd^ z+1y$=IyyYe;$>%7!%i6f%slr#B`GyBw-&7^FD##Sdld5V@Q>$|OO0qm%rB(QW~52~ z4`NkXas&0uY6`V#I5fX*?gNBLr+Oc5FMOZ}K8pC-sejHY#?EtKyy3(G0y=tXYfoC` zs5OW_(~Tvu86ucP{rAJKR%yUfXNzLZ`ewWP>4U`t#v@+{wm8I$wrh2m5kXQ}0+|Fl z@`Z&YABT(3LyLRBtr;0T+k+qiWxQVF-KZWVV#07kV_8`l69Kw6B3x*0W@e`Cad6=e zO-)Vg>hkiHJ1i{HsUi0&tWld9^}{+Vy590Xp9YNjbg1GxZ39Fn~e38IWyZHPqm z9Fou!@XB*QZMZcD4}F2ADXEC3-(q6+xk`_;Tr(ak+1)}1hbAJlpZAn_7NWmJ3 zanGNE5}*2ay}H<)%sn+(3w%GB%^wFtL`+0f($v&sER$iopV__0!2+3ir^Dn&;x<(= z%mE^TW1e^vzIh&cag~;u$~~F=t~w~4jD`L6?vIQ)KAXwxA*Z#iJmS}pQ=f--q+KP2 z=zrgLC^1S}#rAP1)73DbepA9Ou@g^`a=jNDM0F)M-w;l)*TIQJ84nB&QPtMg9=I%@ z6Y#hSAo)zvVz#LQBY1PXVK}$B8Ej6C#efTM{)s+j^ud}!+k3ce$M$_}F)9wNVDhk9 z@+e}>QX1V9PZ<4&cZkG%^gWBwk#G^_z3j1UT3V?`%&e@=dE6G(+vu5+)<4o`L@b74 zuipxK|FCy)F(vvu2$w`HY@z?5YUB$wN`!e)?A!!ziKDxXtTK@#jXd;~e9e~{EZBT% zFFI?uSH^2 zDX|XdhOU#2GaI$K2Kf2i9&ZF(=g^HNQAhO~_;eiNtS4&;d2?{uphg31% z^m%dZB)GMw_PHTO*3Y`Wwjy~*t=f`ch^G9!MN2)!mLA7mwfz}QiBd)MC}qj#WJR~f zXKIs)z7Q|syD1$p_L%W5EvWWiRu2T~G|`g2n`H>}vMe{l&P~_QGrVrf_8YPbVItW7 zZMFDgp9SC8^U0&0TDodtr8dUTbl6RiLY*<37&oaM5Yu`Mo6Iq&MO zbBcX;PYC0+3E+9|vJmDMH(Nfs8CKg7JwLQWUE6E@sjT-jxInas!%i6wUVJr94_ z5TV(wlZ4Q07#NE0*0K5}b{a5JID_40>}6>wDV{9)^}oqJ)KkHEw&@ zI8Q}D+XYF&V!zVtHC+E&vob~!mf8~=Zcsd_qS>n0+tw26$#= z4i!M~?&kTx1*@uS5CZ~JyYQstX2iWINP2AdR zHb2r6li}}(T{_PyM4!$Qo+*&~FQ1;C&OvP~IP{mf;tUcoT?d&94;M|qRrK-lhv0GRPF8hwH60#4zUtBOam|Q!RPW)HJq-;__1m{^kMKNXp zA`0`SVc+cR*PtdSlWyZR#vPL@br!>Cx49@gH}^ZkZ++IYUczT?08{i~+-Qn!$@A~Y z`SD5v^oK2VyUH1Td{w1gs74aw=75_OpyZi)tImUHYRC(as_(m3?*Gf^jR zZ5SCD4O9g7i>_AEmwdV}-kz^I)CP4`S05#Jcpu%VQ6`QIecPcWiu2zJzCS_(&?4<$ zU^g0wtyNQz)81Ey?!vW3>c-k{Y+}2boz|MimF80VZW-BOzpAtdDkQ~s4{Ut6AP-Cy zWwNiZj4ob9cF!GS53@Qji_I@8vK&RB%l^hdteMHYsu@Sg7TmS?kAyX*_@OmlH{OTCCE*qPH;6;a+baaS{) zqe>jghaVDYTUt~2xl6q3-m1@J?%-g)>HN}?OHEbPJO_WmVQo+Mb$MxSyVY8=(|ABY zz##{}PV)>GMtjW^ud;`{q@?6?6(MKK&CQkh*B-J#8k)9T6P-6w(P}y@ zByK0~B>TUwggFvDXuf0kdB_MiQnhIQJ_;3)}tQn z@F@QKy7ZQ&rmIdh`rj-JEE~<No-R=L8l;ATy$nl*GSu={tf3I?Gnjl#*eqe?jo=7B^Vsn z?6^;g0_uuE6M37Frl{ZPd#0Z#_dA4$nApa~Jv)$wG{NFv8x%444HYj$wIuSY$Z2nZ0UqhY^M zAYazEuO6^u=#+|H&1qej3@b%M&ZW+vLs4o!Q>dC z6FG}++jjkjsjRH5ok3z#@byrj*?Hq`-c z`*gW)ilWj0{5BGi?w`!6i7@J$hZ@}pt{;|L<3-0cP9HU53JMCYKcV4UYgyc+89JBm zA00jRfD_>4=b(Q%jpt|{*yL{;zOS?;&t%k<#9g2qx9h&lNqOLP6lwg8IU5q-X$LIZEV z4T0}Vv*K4lu0x?PQco$PmS-%U|CNnBULP(+xy`Grxf`EZkS#}@;<$@D{Qlim3@%f! zo~daM4GwCT|6%o3n3LhZe*9-92agf%2J0!`oyQ{#-I18iS*{?flq(8HFdb%$Ml`wPg=a&{g zDR1}(nOf{3pNB1*`r&b?{sL8`^i{ae}*MIosc~j zv6yy~M411~Jgk}c{mpOSa$i#r2@%o2|NbuRjfBphb^}HS8?BaC`1weyJ;V{PL(5iw z{`?8Bp3Kfr_d-;#|MGA{YBi*w4Oy7Pgk#-Hth@gc|m;JtqCo#k3&du^R_0;{~8W z2`q3;Ji}!-w&!g;a|+#d&~b8GZq`|jo@H4|$Eqo?jb9nnTbD&RlcZ3}5q=^^Mn?Q- zoZ&ou`L|&zsk^&d^QEaNa&RLS&x4}vczanY`goh0o7?shpu?BZHDwjw=XydAZF2n( z3liyHZ+LI~+cI_9YH_&HrIxRFSRNL+=Ck-g9d7yCJ5P=}@Fh@;Z$wTTDCfBP_=j)0 z0|bNb_bf69SlMn*^~vrk?e+;bx?;nt2rKAOzoBEpS*VDuaD1izMRVoFP59ry!?@{_ z`#M|j+2>dUL>hUG+RpQ_JmI^&LeBg9`?>n2;Gca+ZkxBzK6dn|0_1Tn^F0CjVlY3_ zqrmT&)ZUCw30?g7dwT)xNsWJpDa(w9wi)vL_{_FTl7A@1XUTJ4b8B%)Du)Pr(Do9NW(D5IvQ*dBZl%aW-@vSUuQ^dD z&xy<}ENCZ2AF5_>6rVNZJ^mfm((Zb!A7|xUs?twR6E(E*!aeRd5y|$r<_EQvo{_;V z+a>&KZ7rr|sq#S9v+sswEVsG>+rQs*qJE|VL&7*9*L^nqpccAYt{V)`k5{!bp`ox* zVNu{j8!Tu&HPzMgm*#bxcs+y4?b7AVUtya_O9ZpEm^D!Eh=Ysk zrIaTkyaTrqaC4k<-;c(&{?{H_lB}sJe3g0<2o)?HdSBP`e3lTRbdOP5RD~njbyM1U zIjcCcvVfqj{$(0Nt{}X*nFqPx!%5(wPR(nnUn#R>52ul$ol=nS#;E~z^r;uPcYVKET@+Q(B%#@8;jyo?@vO}J3 zT_>Y?%IH6+$Mm@p0Q?$N{?5@Cy3xu!Ui)zVUyo4V$qixs0uc_J8 zH!;a|bD98I;m6kV;J&(pf^X#7H@Ee4-Qv>zw|=~y(oRF)_!APTFAUk;bR;`4x;0 zp)lQ#M{B1YTaTvcIzOgtz1z8*<Ni>-{kfSqV*3iIlbs8i@~*tO8wSjas}clehXB&HBQ;(yWXrnJ7J}V8=LI zWLD6pjPQ`*{SOc9>t{R5+uHn0G&Sek_S;PWELgHD&AC2w066f`)7XP~esO90>HcIm zQsj~XJ!0T%EM-1%WRR1U)gMm9H0Imnr9)-I_ut#S4xdEz(}dfd$%&%LaZV-Y-V!p2 zLrx3H9+7(}o2U>&8lniBJZ%ND2Nyo$ac!)Yko#vxEG`7yut!SzKkiCm$ zD+&_Q@EV%`MOB-q(0?@)7fFPi)}4~bZEysX++)Vl%CdD*OIPY%r-E4foLUlM<#U$H z+AThUwVx#N;~6wdEaz_B-?w9tP|I`dPUSuCNn#48G8Nkt2A+2BNUN9BdpI5aKSTM9I>e z0D$a;UPvx^QP0E2#KfGQvW2`A-ihTT1sK^$VK_a)TyA4yp~|3aC!8#d2p6nBzF1ff-EP-w8fh8H`THHFQ`?kP=oL7U03B zDNsYR*_fD^9I7hHwC1=cU8_ucf@K^W4*NZgKEE4E5PkZG`%=w3W_`Shw6wH-_C=ER z6WV0M>Zh5fBTD2$;9x}!3=Oug{LVm=2;2xmK$|Uz>$Dh-pW6z&n3%uzadm~HIg1s+ zQOirYxxJGb`+4De_J`QH_gUysbe~9|wyd%e?L}B9ZSHhtC_S=;TT9ECMIgqs6Dq`7 zPD7ASOH{)K=EoRTWs^?06@I zc9fQz<6QaBwYAl?wBYC1PZx;09RbigO$9%iMm3VgVmJx%(&Xk)jUHYcV!nnaCH~#a z5;9{8pS^bKC;aa$;lG{e;gJ90^DpA>?(SG%YFwGV)6Ji2iW z^TKD_bvz*xl8~TZU0>hLx>eICrU~h5X{Dqcz2_;*&`1b4?!dPR-jjq-qjZ}=+O5K< zPtKtLlzm3SXH^=nXa`uh4b&C+a$bP=u;A5pCjFYqS_yJ;asWn=qs9V|TJYPi5S=26 zf1L#t6^tfYM)N>JV4hRpPcv$xNQ)?XY;+EiR+o}c2AWha*Mt@54f@8)uwU!z-Ms~l z&HBvPXBQT(Ho?T69q=|@UCr3=V`;7*5nWy&$FDly3Q0kj_46y@j@`+ed(sbXJ>r=q zen9dVQ_J{CFP~Y0(6fc)yh^ZlA`52Pg2X5$tPdwaCmsJDIeW-XPW@!Pysqw(m{|~# z1bVXtt0j}GIffL8FczXIZXZR$?~&Au^_#ltg&JraBPDSL=jPmUz+eJ1VZ+0Gw$7)Mt~C|qpsH*-4-?M3glG3kuY{EVHvmJc-%jS#S5AX0!P4PEoIEDMLEm!J%=|2*?g!^OvM zDLz~+>^rZt2(l1!A``+2e`_^i2Z|?)OqF$@3xdS`FdS3jY z%SQXvL(5ihhbMLI(aDKo1RDX4bm;I--+w)U14Rlk=|BhgTt)wem+MtaJ8fRJymS9Y zr?tH5va%61&|80jh*VD{RdLg$-jG}P7KJRX`p3*=|Z$rjePGveA9KMjycBU7Bb z8yX7AvWeXfBafvQWhHq%z@@}a+eq6Ej{mt4Ox54 zZYt-ff`5yGq9XB}*F>FJ=5DKtMR9TQ%X~zrI2?HXDTcyr5wy5+z*OvbU;1@zhJu1! zKy1)^DD?wibjM->S||bO4=O)WF4TT9yUU_M`(JgdvJJWa!9Kks9mCS4gCQxX@|s3%slZ zZK9l5k`;WII2SMXNA(Cf>M($(u$gpgNKP8vRbFt}*s=x_A>Mc;r#%PS03#FA=zbgP z+f>xpcZ!hkbsxkrn1v>8v)GlCS+^ebG%NWMyZAj$OMM#V_`{qk-Fa^?nkzo$D_Ew4RFrIvr2Ste>C<5=cwLDzCTe?++B-;5Rg&&GNp^K7@( zhD*hL!{3Zj47o1!jLE$%LypRy1)+={Cbn1U*dJb9iZby-FTEvgZ&alk{G0KRe}yP{ z&UywK^KuMG#dseE@UIgh-Vh&z8fcQ(D)#w}HT=2qN2;i-+}X)h54FIOVSrZ;uc%P7 zc(?8c&A}G%)YQ>wPS9v)HeMob%cl*yv!w11(k@=%uA4 z+DR1hST#LQ?I;daVB}33-XV1L*cu+EZ|gM3E z^L&L~YtHo{e_Vn}+Sw7dT1gb)EExwJg;&|+fPU{xjx-X<$B&|K-<-YUR>ZJTv*iwoFf;&+T-V_k0->wIn_;dI7fZn{Ev%ptz_{U3E zJ(n2=i6Z@lfUh`1pe3tkE|uyPGQmWj5DN(rt#GiP-rB;HAp|Y9`{55Ut(LQ^yu3V` zh2y?&E$4elD=iocN}$jVAHqUO((L-kPOoEqun=f@j$bIe}jHgDiH*zs{I$@LPYplK202!ee7FE2wnF@j*G>_bIs_#)_rmavL}B%GZM)+l_tWsZv7)s z7z+8?s6-1jgM?!Nm&U(95u>05ZQtz#Hp{@j zXBs*>izED|yEWO)H@ssqn?_!qlSLE?|H2_^Lq8l9Lh(jawYV?HVDq*Tq$pvXGu5=4ul2>K^ToD>BzoR;>WGVezCf2P6w zJ065+pun+&o2`V-^5!P75sg*|pw^!BjSj9ie~LMutr`dWAWAJy@+7?jWLBJt3V}gr z*au&s2tBTd0yCI2t2WtpMqUfrer@$Cz)>Ji&)pXEEf0wbN0hiOU!fj`oAg!jTW8vQeC>&|*}P~S>F{)?q)<_t$W$ON_eqcEy+v6zNQ0kktc z64(&(g?OxJcMg)BR`fg z-k;oTycT3|P9afwZ_%HZ;VlXKKkAEK<-JTq<+-0{zP-O!G&EqB$aB*4Q>VLD$uFba=K0%h8G=V`5N+p8NCIeKw84 zV`3nTjQzd6FrLOp6e^gRj$em8M%BMdQlgvL(o*lOvd9cF)wqoo?PQW74gksq_2Tn2sTqweA(cX781 z0b+O&_TejMlqC!6Qq!Q*8nUg7YX=pXW1}Yvf=ondbur{VZC%rk*VjA``>G)ly1KeL z03vIrTjTt}{j+y`AmgTwf=sb@c;wL^lkyADjD0SjhTTSs|FaAfkqv|BMH10NNd_|h zmZ2{Q!+b7CpTWKAipx6vx04{LNKLMgl-$hs9db)??5F}G@V8dLpET%lrqPs>tgNa= z;qVH4r~a?YNA7M zEEzxq`Et5Y`@~DiPWJteBHPqnV0?rFz;>-}+8jTiKHnn_TGv_R>cauBpPA)ZYG6i% zGg~tYhxyyf=Dt^<@MUswA8F(}Hyssq+r;HvCz9PY+=l{sLS7A+>FVDEv3zwpGUOa6 z5q4o5sM0CZOKTsKk~9EoS3S**F<$e}atP{0PXqFD+m-JM2-5<7mk)cadFqFEa4KPE z%cTOrsEAr-jje8r-Q6bN5s}WS4SQ0P`Is!?LxwjV+vV>D-j$pxl}wc((Bffl4-v)< zn(f_*yDd7@vCzM-NikT#N-GRM5piUlgDu?=)!c9kV zNexUBSA3O8_MSrRMUgW>n>n8wfITX^v4;G*4^dH_eHo7GqZ%AbO+Qc7z>t1J>PQ~f zycRR}O1GWfP|_)T$rlv?hN>C_na{lhVSSMFUI=k)7*-gl9iX1(75oIu_wZ*n>tJFd zAW1@bYc=?fS8iNPo)%O|@S*xN4ohSmyf%ZNU|ssQkJ zJx?@G|Ar+{HsQ9$+nu5A!d|R}M3SNHyb2jPb@^Gwm5hp$UImc=J`izaaaAAQ?x(BT zZ8kQm?jRZKq;s?(1GA)lcv#~cV|LHCfN%$;tYzI@QATG`a)Q3vJ-@KcHWUsUW37Js z;vN)@H-seNPWs=J&_JbdlHo{~Ssm-Qg3D$_#TgMwQAdsy*WO`QMw1>KB#1@t=Tcht zKWuTYappTnx9#=~Lc@`xvo}KM%+(qx0jQd>k};o#>-&z|p1(f=uQ4}j?6(64PbT|5 zIW#4W7{wS0RJgnQ`+NtY2Ut;me}8f&4pRR;XzRoIW$NHtdl@SI2bs-~6Tw}GQ#Z7l@J<{S6wD-h)7hR21iLz zK?pt$?|h;khxq`2allCzCe+w9cxabn6^qv_#b&+^UG1xwh}oWi)M%ph*=KunM zIy(A?7`RRowp{;%@~WDmjAXP44|I!%oI&(~FBk*qo+lG^u~Sf=Or>ZnEo}q}_{2VO zDT{Y0x+#)p{->vf8C%E4TU&qLj!(teA7IvGBS;w*Z=v2-}7&io_sk_bDqtAho7P7Sla+Y^a-1AIP2YieOqly6AJ&8R*>+|{x_d%RY0 zo8I|2w<8<$o5<%g=OPkw@O)$?9e0v!dwv*@N$aGLD^2iW)Fqb#>8#2sglkFyBP`fn0>OQ>`;LYBL-I*x-Uik@KUzTSU=e0oKR&e3b4izdnX~ZmBQBjw9uviEVH10AhwifX50);XIa60ZU6cl6o8&7dOABhYZMd@RLs?{De6J zu8lsPcPKPSlV(WQy#r$;aRvUnz0V$#pTGq6yjN;qR_}g0NG5GzK_ws{0CaatX>l$h zX+R^rpRpYpZsCtCpoh?)z*$69xp_Jv}{X8ttg%woMiUyNt3tul(LhxJ$MuO}$(6Y~@-~f348vcGFlbi4A za*jjfNe*x~#VT@$es1#GVC{00<5&ra2zx!Nm#E26rzr!>+R(=LA2qCrX=$nosJXc!_wi$7mW<= zR~;WcMU=Ef)NqdfEXd19vS2=_+bq>PK0durNsccX@|aZY%WrxHj<1KBo%Bi&#PO!r z)(kPtpnIjpW*mvEHZwC(GE~TjuT;)jm{hP{zoA@n+_~zW_el9ZY>*Q;>4?~i%Qv_AhkmUl9R*H!jFvGE3WJF z_r!obq76S?O3mV7k~&mvIRYh-1G09z`lv?So*SDyM6Q69PEMIC_j6{LY?#3hhfWyF z>F6F`O-47f1Z9j~40%0MOJX!ifm{|>mKy^*mOtL)=2u2d5&xoIqwS1V?NY!*s;-Hj zMh!Gc`Nd_30!HE_YViduP*8`1&o1_-2ByMj3GUH8n2t>W~=dl zYaYB=l;Ia`@W9Ks$K(0w@!5_5ak17kWK8&G{o>FjFX+0}Xv&GNip#b>K!_BGf1yvo zdT_#qOIJ|Pxms}>r3a(?D23myhIq`rmLtp4t-yzcW?{5c0qgbg2%pp+n~8wSp)l4 z2$TGX7H{^#^Q;MmGF|yd+3M#-FAcis*b4duoL71CypqXla_K`@ z1MDV%(R~&}v6|I8`IY_b%g5jKwu{C!=Z+)HO5NJrw5}Da|DHyEqLkP@0W_$AXVx1;*!EXct2jx^BTak4%t|l!YC<9(cSEj z7mt!3i^(*&CSf$R%$OTtw5RSAgc);7eY26m&*YT<*XcJ&$io@M{t#xH$h;v?yrRb#E}+g-!`Dx1dPnj);U5ubvfHk{{2z!94-bc_ zdot`+S8wi}vN#p?#fJy$lA7EdzY=~@utVqP{bpckotNj^*a^NZ*e;{^l z-H!Xu#Girdq4EMr0@+etWk_E7QkE(OQa{2qp)4#cT=+yHQ>YGB#Y`6-SXfiTdQq-k zSX5eSBk&;=+z+Bbjf?ce!>T#h+e^RP96kHyx-Ai{arZs`t)NJ;-D>*Q{o>-{imtKO z!cY$wHT-U1g~25Yxc2M zgDaoW&Mr|=VX5mXdg{9f&^lH(HjK;Eh0#GqQpVP8oh;Yw>_nKy-V49{2~TZPLC(YD zY&}914qjefaXx$Rw$FUYqp=Y0?!}S$H@PNSfXQemXv3B(26%?a*oV3e0l$rJ-0X9- zs(r%f<=>gx*mw!V3R*8moo3*uS6Jev!%mrndjDN^YcnUXW7_=t_iy%HF=2{2{`(*>A5-1iTWz;a0qf3 z%=lOVryU>AL&=f%4i76;!9!j(SWi#_3E1R6u31lAqC_CDWSBnu!rvkr{XBI)(zbkh z5>o1iN;M2Gsz2Ab1V*6QW0)A3LJ5%REx>N;zRJ{4S{g|hvAqBca*)0D*F*ILvTt7t z>g(F9HNP0jB;cg56d34>7YNxkU{rSgygUJ1CkR-oHuPEUv9YnCW9|5@(b&>N1^E#- z=3um>!i~Pew(Yu{7k%tM>Tj2!kvaFN0O+fsc9{-@7GGl}mM*pAJcNq84#)YCEF87L zR+`^u73JrLdQ7qj019w(>^C1UM$f$%NN--U4iID(q_g~L z_l_vBs{|*bz_9=~2h{L_f?swp!#0*5-pqn+Q=a4U4cfHKbn*}0Y9wSV#pvqy@IZqXK%9ci@gn?6Dv)%;9gk4qyN)T9bJFVXBYJIYKoQ82ha11i~+e{(Te7Etghsj0%!$ZdY06i*NmTEcg>_#INJ zYj~=sy!kvNh74=L#ljc|L~L<0aOKLaPy6WT$j|gDQJKeieVI{ywiG&%bt6OjhdV1P z3mWu?$<)sQfUQupNkKAjb0oB4h?6JxbDA7E0jjwfJGue`wR)JfA(RFydP|xzv0cgT znKtecMPh^({CWo`#|Uz?Ore#5gdv)QMxEw({qP1czTCy)Qhn9DzSq}~uiYJ`wU7$J zexTT1Gsc_``d#ck<`i$QyHf*?M9bc8mdn%Hf6wA$k^;N0#EtX5dtuj78^=xIT8MP}gp<-P2imeD37Xn&YAv zcV|RO=V*5a=Xc9uo%{-{x^;Z#%t#a%-+RyqQ&t>pZTa?r3+MPb_&J_T>up6xRy@o@ zJ{b9Gmm>RI2_P#pXTA@*iE@@QB{~{_E}5O39VW2Yaz=OUQt%siA1#=ME&|-p5KVeN%mZeZetHFOSZ2=Nru5)!%PXbg@Fe1 zfr#o*v7c$c!tubJJk$>C6&J@qxRWJ)7<|ro1rrV#<0rc*9j<3i^k9V%>*r#P8+?!X z`t|F{$@vT}yP_Uk`0d5O`wBaQ59sPRzq84H?@!nZAGo$AyIIKAQ&N$B{s^hB zXlrZxRzVtib-3h$0uQ$Z+y?Qcwho-F^#7^?s#_@lV#LD{g)`A(jxslJs!;?!revWE9M-f9QB@fRBhWyF*sYb0s zig&-@n-OHPQ8Z-CGfQ>~XwmC@3#!W7n$&9j;lVbany?c*$N(H*%4t{iQbcY;UOcZv z(NZEc6$h=D!xL_#nIXMczlH1!pvsi*sesrGaC(D z1vMuqH{m$$|3lzF>J$`dzR(?Xk4pNp@SEGtkaC~dX$cUa|4T(@oZ=jMYUt{ET&$_7 zNjfue0A;{x#`f~bl`qh!q`5;R4--f?FAuSGb|&@n^24)rwinTdgr{bVH4`Z`qvN7* zzga#Dmdw9jQ(p##`9)xa&I0z9B`bR?ZuD0b75&XeZnb44c8qm;%uaUhkx8-1BFYS1 zCDqj|7y877KjV0}1pY%&0wyIp26VD`;OeASWLh;a#K%n{kDmlF-vX}GWP!>4DR(rL zdrKV$0sKKzSQ6dS>+9LKtXhR;OUGST6%}~EN2{0wKSvPKweM;*F7DE3C+R%E63$!d^w^H9#n!~NFt=HbO{4G>ZT zF7()S zdh2bAL}TEh0@Af9I17Wc!#0xWrRUpSgxHvNr!@%8n`{rju3S&7PerAKkZ4b zb8O&)g<@U6jk8=*N`*~qIFcZ>e7on}<$e}Ju^$xUElUA?CJ>lwcN-F$TUzedR#)*d zO4`8CS!&5b9Izodl9|6MS&5v4d)n+|@ipYo|`Maz>VgPqquKIw~?6?Zw&)-=O=d3UH{jE4hW}t1IZwomxbRvV( zCP0NwP=;C_%rBMC^Ru(=el<{cE|Y+xrq4hzYrXA|B$I#Z0R5EA@ac;hsydE&CLW(` z1&Q1lJ-ercazMcS1K1r40k`LVkEsDemo5bTv^R{563lp?n8&|Z-M$K;cVb^0Ah;i? z(r@toZCP(2l|&7033r>VT|bY4kQo9^7LOV$`a{j(;YfZ&1~oB%H>*CUR_~jA>sWrT zfHVZ>i=tzeP%Hh)7t_A8i;L*4y>3T)`?t&4agq(=9`-%h>L=iI3ZtU+SfGTDnI~ zDuCt7yS{b3o|(K2VUf$p3H;Q%Qj>oGnWBIhOQip!`CbGp&>_Z~fxq$B8G%sl$0C36 zh}OiaRxvmZ!|(!X&XURK1Gu zYi+QPpw^2_>cUO^qQ#~?z%E9JV8!)k#xe|klA(WFZes1EO4OR;KUSeh$31e<6^qmh&qU$raL68g3PW|F!_G4@Qf-PGPRG*U+U$aG&!()}Bj_ zzxK-ra~$Rwi|S;}PGnba$YTHE!*64I?EYB!f|A--M>);`d=SB^$ZZUHG2NKMThC{A z#SzZFH2M))%U_2Us#5AOWH$*Iu?YYq0(bJ*2}q49E9}kY0t{6~t~xmehgmyF3|kx# zu+ueZ2lv#;Bz5Phgd6ob<&%n3r*ehwO*3$SE;_2wRLW4y3qGJFTRX_NHxbHom2ORP zDc@63xVJr}@w0Kn-=VdS3?$z7SSMM2WFUwDiaqcXFM0ZSO|5p>Y!w~6URs=uQDl3f z2URgnO&vM2q&S6m?koyZ=6a<5!Iabbhc8ny<<>yrJfDA(hQ9;&FhNdy8_i;U?fAh ztzSP+E8ybM7H}3QXLheZpY{+8U|n0t+f881oAvVY>f}W3Yt+ma?W<-Fe0xwC1)2+> zyhjQIZNElm)`}H46oC=}YCWZUzymO`6b_5z$n(|clE%N+UcS}2ZwUN6E1p6^>6ZFj zqIEESj!Swj^bJajtOW?eMuCIbJN`4>gg{suQ3d4XUL!cKWhvJGSVlF`WRXfwh)J!i z+8kxZ91-Mg?&i^SavaClU*CZHc1aYqh%YH6W0ekrf+_1VZ~|x7q%n+rx90P7K};P( z`*kwVWB!Oga|EH`(y zDJCYS{G#A-a{Lef6g@u^SnTm{%co)}6pD_Snb{jCGe{*>QM%ka)+i}BqkARwBSQ;k zpR2FgFdpe_qWNQF`Y!2jy`@g6h*Nw#+Xt48&OM|Yj)Omo1 z!^7bn$uiEr;Drqh45HP?baZ(Du>L0_e%5pOJi-ympsu_7I;uzYhk+6gwv`(gL2E+T zKM}2W&P8RmMWm>`TK7@-pW9hzLDv~dhspV|;nGKh;yD@85G)o&5&L}tF44P~$TGOM z`670QKYu1~W2beE8z1iw0nWG_Rn`w#1>KyIEh#oy2=QJG^*i4+E?RITpvm0Vyu|o4 znxA0V#gdbgw9oUT#m4Nd&ieMwAV?;n)kqVJpIJFMUpL{kwJWQt<|^O4|Ig*d%F1ew zC}K%TR-Ikc&D;wEQkFx$b9CL}A4f{tv-@Zk{}x2A*TKnyzS z@i8b9EYNg)tk8RJ2mP?sbW8N{8?N9j-7%)jZ~{uB8Kh|5&G=bxJzZNuRCHl4TciW? zX#H^d@An;Y-phYVOuIJi>H#$@hw8L>sB@DKnjhHSpQN+8xd{b)Epr=82oKHu?Uu6x z#{B;mB=mLRkJ+Et7y+D17dH4U#lX;D$rS9DA$>e;yg*5E+z!k;=EVi}u;zp) zsY00QBijp?UbrbVPWpK7g!Zy-?Oy<=I1#Vqi#=>S(2tRRn+@p((`8rduU`N? z4>74!!U2!PEEetAxJ~pgTl8`r;OJU@^JsxikUR3;YE=)>1?e~K6?*o+ZkCUq6ONtT zO}e2BeD-9T3VE}skhS^gP~plO7r15Y6H4`Yw`JN@rnu$1H+WW$-D_*Sg8*Lb8DZ4Y znNH1^zkQ!4Fg6V3e)}YsX0N%)5jNL|?y-ss5+viJTw#T~Kw|~?NZ*=(dt0yu0#>d~d54Bo295;DME}qo+no1rNn@yCmO?F04u0s!qHlRzT_2 zbCudS_~4t?%uOuj3DK_jrbPlV$P1#k+J{XKR(05GXPX$$^njijPDW3yO zD;OKP8fGG0M5jR?*B%lB*c74wD}xj+tMoi(A|(=IN~!!o<1->d7^i`XWkj6 zFAwYw$~-|V){Wz$@4JiB4|p>H+x<-ih;c?gGfQWin3wj)rdY_csHcBS?6Qo^g<}{@ z{^S)imCzKav8BZ_H3+7GT#Y+C}>`8(pgibWt=@-v=iGTkk$LP`! z;AU!;9AJ*Yym1=NhzCLZ2?mHPbnYR0dOE{DPL+x?3~&@lNlBOCp3oo=Ldc z3{kDygP|&@1Pe20)+J|J2ZZ9Kp667LA-hD?4nTGcoNqq$r&OtDH<>%ZkKh1ruGvfZ zyW|{LSCN%v+2#82WYxt%_tbA5-Wyav9$CPiQLfP(kJKfA(9h96kKp4n`=h&(jN*vn zCtAp#pf~QIq1^+z403@4aBzKueS{;UV?P+_xAhDRc&PyJ`H4&>Q=n+2Lff23`jMPd zL8FBMLuGp>yGQSy%)khRMTrL_8i4gr{`AADoe^($z9VzkZWeA8MpT$hXT;dE)8uo$6IH0-)Bix zR8?KzMJm}w;q~+S8%@mQYV>#kRo9=O)8!=iqA9Hr+&!KFsl=j*0 zL}845lFK`G@qYbt!!ov&V5Sm3AV*uOw`9yNk+E!kx~{tFki)VKR@TEUE_AtTJ7va2 zKIY~bkRCxv3Y}*`D7UI96Gc~3Ycdla^j>)JPS)KYCZ`FzfliG(zzCX4Essts*gMgfVHotP7Qe_FI2L7J_FH^TVSs^=;s?8e*71A_S`(`SiD|2HEXfdb~0`J zu?_x6@2gld-~u*_K6{pp<LN6_Zk#$oTF) z4C*rJu7*p63#p#pRc=_4jQ%J&=1!zCt?PuD29@bc_FbAh7k%&^?%r7!vM7~m)TN&&7wQpnbtHW3_7eA8nFxRU(W#1_E;AjpxoRg(RYjRBeFzvXq z>M6ak)U@QPg@P&9&eQ~v8ogJBC#LELb`rMNiV?X=yUFm&&vi0A#4abx2(Z?|-Jvzsr=BZVCUK87K#djG=Zw2_a8 zKCTYSFUcdf;oQ905T&UGtvidSwnj2vyt?D{KI&U@V8z9$ZrM89_OsE}!&n3c_gL#{ zO8M{Sb6jInM`-o)+2*M%>>3F6P(sFAWQKYE|NjGYo2CEciB62X^5e+_Mh-a v1#k*p(meLDzzz;k(RecW- zh=BaxHwGv-p9Tbieto4Ruj8A)-{lu*WE=Ew=;9WdLDtBS-tH58myl{iE?{;|tDu@gd_1Qs3sca@6nzPQ7EOiqqS zcLN>jZ@v8f{rfi_lBq}&d3E()^yKt*>gweG-|GOiKZY8kg6h60=hJi@EodkyrUD*# ze)mHU>7@1m)!OzCC#kPkf+ZyY7#94F;{|D?;%&mG%w6cn^x;t7ddu6>npx z2n{EDNR_Ct^{JR8TQNsaT9IAx)P?dxcOgbv^)ac!s^5xxQCT{Z4}ugHQDj?d))pztb#EVq4?)O;D#?Er z_f*kR3m>HYab;TA=NMa2%w2TWYhNtOt0S*A9TQn`AAul(^m{EWAp3D04meq{x7Fzs zz`ljJs1sIrEv@}mOXW`MeLp)d4x7Ji^s4H2F+^YclyGRAou=AT-}*d9x;sWGg8OE0 zXy}Gd8{R(YHR*!dps5MS}pOU|yYl5l57U*B{**3|C9-R?teI8BlodaO1kMIaJ}X zVng7qc@_HVa9CNUHRZ}_h3LNVCsdtD?UqyPJI|IwoX_+i92}f!OG`^?inzg+FZ+LM zP;&%k2B*&h>o8@(K8yAT?x!ESgSpJ8;BNgrcxVQBVQ80;{y7d5++RE_^e#aQ-(ZYZ z*GQJI)C~tt5hxo%TAKNWThdxDvspZAl*n2jr_WPDdSQ9l*r*Nl>Dbf9hq|+~)8{4g z1*6oG-`;%Vt{NOxC_u$GREQS_D%@qwfwF-yu|K2}<39-AMTtrC;eg1hy5ffHCI6dipm@FfK>9;|9+YJ7aW>v=#2K0)h$n^t4AH8{xpMh8-Gf|rxi z-hUR2^SX`CCCig1J&EE^9GYRih#E%v@~|*WYjb=k8?oGr0IUKg>x7@H6$R)1hz?*6+H;Nb}rhQl>LY#;>Xi zIC{`uE5L2DZBEOOcC`};0NB2u7LABeL)Ec z|DblG@x_*9HE=ZhdoC>%dp**UnJ==zn2n)x2P>rub@H5{=DDrxX(I}3DUf`hgWqv7 z_>1cK9^>LcpzHI!-%S-gJ;CJGxkpB>(O~S4RCHCJm?RO*!T}yneArX$W zk*Po#l+WCPFqYu0ojRkhAF>9msjmKS(LRYdg+W=vK+wpQF#*v@_+xg9_}TkUM(d>V zAuOao#h{vA$)Gopf2aHqlu!AFTG`)JrBFWC-4j2F7Y-*l3*c7a5qtQy4Dvoi_4EXo znXP65^&S#ORofdh-)AEiQ0e$ss_~5m>%B1BD491QvLJrYvvyA*Zw@C)@axg&$CmbBeEYH$QqsUdzA(H`3F!5Zw>a^*G{t7&q zR^u%Q2G+KR*T9Y!Begtf2*0jlgJeCO{q~nj<0UOhxzH)M3yMA+7Y%I8S_2G3r&VYAK$nQM1Jl~G`jraHW11=6EKbwep7B~i~{GE$RI4IA2ZTyqlA4|Hi zMQ}mfkqaZD_aYGFYb%n)xOH%_((M0sVk?YC!baEA+uOgOpx~he-5lhY$RPejA37qe zu}i5Vhix%J&+!?1ym+df_KaKkX+R2_3MuvvE5Th!Ny&?$_Fscz6T!!$qlv@}(nTHz zbQO)l>IpA)S`XE^69l(T7c@Z4c17kiz%$Y=U zz?L-~wF6`1Fx3$ys?G6lIPDDPBmcHDl_#&}BQayg)DiR$OTvzlaDJ+aSGUEvQ0-=D z+7|cp^z{3&c68y*Kpb!P*S77vh~yCWmK+#9+aoDt9zJ{Q(KBYAF`gH{;-hhy+ey8_-(uCyUx3+b59MEU;y9AVrv$M1jSLVtq z+Pe03?fQHH{N>5e>P@#M#3>HGI%Qj&TyK>aC}gf>&QZ6)iy?@>AD}*r3%qOBO2i@EcxCxjFvm<7PsZ}#)#>U2- z7VGgjF>jxD64(|6os+!To_X=+3A25jNC1CZ8$oyYPDf&_F$SC>x1ROrj?ci*OGQXi z+xxi|w5zGCZ2btHWpa&pWb*zOTdCvA=rNj`KA@7{IKh}$(6cc2kSGKSQgxouZ8Bm; zUT#hmh-j(R+=mz#+ij;&VavNoUUtW6wLt3&{|-~Jx0&>(E%?r{>8*UcHh zSDw!2MJ!8(sGwl^d%2B{5DE|C`4%@?Jw$tnQBLUfCIeQo2J;UvG+Z=${d%Gv=%Tl* zt)ga!g~&Mwd{sKf0t&_c0L38`LOmWW=cUgYzJZ~sLTeETlW z?|Z8Er;Pb->qORXjiVrf6r1hS_?>4lz4A=W0$-{9LWH`w8e(?g@VchwcIIZ~qPxd# zi!Jw~1MgAKzP}$*QrLKrD>7eXsqMN$=`L2otYq&Z_<=;`%VZp=+8B~PgP$$<``6iX z-P(D?LaO16vqhEX&z{Ylnx3zY$oh-ZvorWJ4h~?0ndbsHwPR>N(6@|fb_kP-_~B8} z`9nPHcIyh=pjnC7Nmb*yN{akYw;AUo^2XihwRqx*(<<&^7`|xqmh`;RZQvS_5W`0S zVSE#eZT0Kx!oosh+j@QJuf>iv~I7u{1gp8u5+@N&<$5Fv!tZW6p)F&NO@T`P*5kH*Chx^E7WK3t8O-dhb& z&nOxF8x*M{R-x|Qoc<)r2@g<>f<@}oA$q&F2e1)0F-;*3fgOk$#iSRGT$o3Pz4dG4 zIJ|cAK4&7h9=+ew-Z*h=F(5LIKwkgBE1jf<7QqjPrXnA=R(fJZ8shy^nI z?<&yLOQ<*1dN7vqe1JqYaFa-MiBFFwD`jj$j`O8JPXF3~%4hHWoMc!jtV#|+$2@Qn z4*Knc)8afZO%!<0R21+)o+N#|7G>HN)Apw>>kd-ziX=C)o&N}nR9JY@zQq2Lt8}{h z2OR&FCI3cmEC9+W&-s!ki@xospCBtic|Yi4+2`E#e$(}Uk%2D4h0YC&q{Dvohn#Ho zxcO6Zw{JsPr7uNQm-$x3h$AR2<76LBl4S3<)<=J;Hgx<~CrhEgr!a5Hc;K% z5Mjl1&reZKt7Y5%J~ub_{N2BncBQA*GzkFG+wUAQ$D6ILOJZABOnYAvjCgS26tQV( zs_^L}wE1o4xL8}oTNO?)c0I7%;yMqmCx@AX{?5ysrpyoDge7sop0f>n$cVjy{*x``vSn-r5|2GPpWi&_N-mg%iR12w4;ly#xhRK zUMRa9WbnrizAwL>2GB{qi3D#%dm%4bu-htFj{>clXq|%3f9Dw(8f*_{8U1%iWUQ2y zJZ8lJ-QMyoIl>yhdYHm)GNmiBS%dbcQ+TdYH+e*iuW&Ge46(jm{3U9N{3pPPjm7qtobn!Dn=jPOo|N$ z->%|{vU87ioPJU3K~6>r;k|g#{=S4S1(G$2dKz)Ng2`KXY@hilPFg_oDPd?fPw1>!zbHkeSmabK#SG!LL4FEvC^+QqWnW_4{&gHL@j`nS#*M-4GoTd=PzLXKG zs6Tx#-+0z;eJ#3NNV}?O=&sh{$|U_Ya77N1noxBA^3h6wvM@B9FKlUH4xjUB7)uBY zKlnzJ`F?AFBxqy(~9#Ow=XbW|qi$20~8|qj3d}N-xFa!*q;Mpxl zUS*k^_KCAv)aU!pKuv^**ubj+Oc1y#I~gPk%0j04G!?wmeo^}-A>0lBCC0E%3B*k2 zNk>F7pQvG@dG@n^yPib$asxM0gMT28_c~!;fV6ejA96#d!E+QD=JFJ{H}f)xk6gmox|U3Ta>~uoP$xoEbsjM|~t8R@X=2*=zj-yi0KVUzT*CX#dY- zR8mN+qRI~kQS=bFxw)975VVTBCJ?s56(>?|y=taRJaH=y(W)$Ct;pGBGk?3>LLW{%jTsKed1R$0phbD|ph+!?f>C606- zVXNst`(nw^TyMDF;g!9gZQ!}Hh#DW)Yyi-A)}enMSnGL*_DM2FLA2l}Or#hfAZ&@F zYj+(_&ob$*61@-K6kX3Ow3^({Y1g~Q$0x{RW5Bj&zWo|f=SVd#sJHI>!hKnYo4}tQ z`;zac+hNzmhtra1CWHT`mg9Ij?6MATVss=hdg$^E$#{4`RsuQC0o0x46b&ug)|;|N z1)#ci>)SVTF$VaO$2V55Fy^HwJk>Z;)NJ|1#3Ev1US(I{86(&HWVlDeoEO{Bg#j|R zm+MKW*`q;jK6Fv={Y3;RJ<*$Rv}AGZal=DkxxNS-u|1Um;HiY}Iar15?9cv6*}HAQ zhOYC4zL6L_E#3c{R-q7 ziY(X=P=Nq;B0+t~jjSIk_~vK0+TwE8>9ksK^=`+$7_peO@Jmw2+dO>&c(N+{jzF;I zI1XKN8pf0z4pH|Zpu!E!Z`Rk>`+js`+}_^i{IF-q9B`r`x-29nArT9#I0)QKpDHRk z+U@+e?SMOjx+WE{pU~DCFtED1dcOzbQovys^ZgLA=eY9Z{n{go{e@;;QUw>>idWvc zlr%I1lnPQ4HELx8OGN3UT2Ru<4;n-=bh>F{Hc9m+UH-3LWeH&cX!gA8VkO{wb1d(I zm_ZVMd1g%wV?bakcn|VvC`FZHEoP{*Hv{^p!oHu+Q!n!oLdYG>=o5Hf)gXO#A7vUC zs@G&QX7((NHXcU>>l0CGV#N_2>&~>BtSwds8$}^8CWbLdCkq7rncLCw_3PJ0j*Be* z{{FESz_xirFX99NbFPUIr;boaO@zO3PafSc%i51>c#`+Cmju(UBk{P=J)V%56;(JK zeg9`d7IBlX@=&=(pvR&MK-f2&%}-NL&Eqw91C+fm1IcOZC>%EPXYs#f!2SURRBYn- zP>*6JKO-aK3R>pjs<5WM!(oz-@G>+Bn3tXskx!zNSW@z%VZ9@-z!TBR;-1EeYH9>R zKa;jyyAKgiw}9@KZr9 zVj&GIOKyPviw@dO__6eqBD#TP&(n5YU84d|&(6-4gTv%`vK0A9szZM}QRO=(!{pZK zp2ej>GGeu$Y&oBgj+27-($wDOn9o+fmBd(L@^aFqtDaKn$3FY<2Kh8Lu6lxz^XcD{ zt8Q^w*I%{UCS4AvE3cP>H-T0n`NNBGL>;FPEVr|2F{T8ERoU<9?j1?xI@)fZfj?FWLuS(2sI6n93=&BsGfsLB>W#8i-XL20c6i zc~YnCy}fv!3BQV(%FfHnwAZz5dtXMKI-QW|&*?OTGI+q)uqt*P7Ht~l;aEyz2xXkM zhs^!C>%-=KgY;GNQ`_=?Ovy_TMX2NDS<|FamO|zMC&r=M3<3V_*$~0jj!|PxleEiI zLx{`;FvpexN5_H^*X0nxZQUd#6h^3Mmt5dYSL5Z^zwz*Vj=)@_FvISq06m%XWGp-k zbthItIM_D!+-#{FnmTBp{)t{O<@z5f6hR@5bYjR7D{>k@RFx;~y$I67b5sMs@Ruw; zeN}(mx>~P33XVAQLY*kT>5`JGiL{+u;&I5&4FRKxK@Qog5t87bU1XLH{x&~*H6^pm0qWbxWAe+uzbj3&jb zu(w#<(&igaQGdFIn?S;rkd*WmK}ra0qA%RHBSp8zwwW;gfsSTdMiKQU8n_;*SErC- zGK5Pf8P;7>R%VIHe@F3#8n{;OB>-?zFMTstl-E5euX^+&t!3i`6jE+)5$MDaK8!Q9 zun>FE^YCyJc-T^zrCulmTr+2tOJ#iMoc3NFkFC}a4Iu*J?bGnlXX06DlVfDpq~CN* z3?B9e(2y7~lnvDgASIu<2@Y@8FM^JzRG5v)G*GV9b9t{(!g*|}?A24%EiEnG;tkI# z4m`Qt3WbcN(bw{N_y$~*Yr0Nu<0)e{?hkht!MBaWOon92x#Q)y8R^X_sb`Zy^`o@u zq-0rV!u$ZNrR#clb5Z2C-;5*%*sc>J;YSGnB5f@Hhju}CRMH` zi%}}6sd>&5Ys&8F<@Fn&5U7sb`c9XxT961ATd$>Xa~eJk@{RX+BUbo*Qsw3}MD)GS zGw``K1pZeFPyR}?|E_K^pxc@L(x_iJ1_c{ARo(8Jtek`h;=_2MrOr|r^usb3bm)%6}0E+J2;-k!vIrWnc&rZ0vHa| zfc##%aM~_FKrMRf}a3bO6>I{ziAJ)qmUJ>V#Dl!{LwENX0xawVaDx%Nm{OLw7?T zM=1%!w6sX2gNwCeFIN1};c<;cry8#Q2op1=aHW!nS9a-B=m^puHcgEIo!GuR+pg?@ ztRywxlF$-Jzi_h8=UK)RbDs0V>PvCD{6`QDQi~@`iz|yYLxC%&cUbnm@imXKk0_vF z?C_Vk=mvaFHP?dRkG_F|;4Pk>p5GmU)FNyPmo--cN1m>1U5eokz5>IGRoA^tM>oho za$J!X{8CBYUt29bt*|q#OZ2$^Ox*9imhD;p&G=wDK>bDqK)dJTYD_}03(B1p)gpG` zr1_2h*4*Hh2;b|xt|4KhktO=QI55@a5Y17h2)_8-w#X&i6BU z%;uOQ_`l)TJQWMe09zc0ZyfUoDx@V!*Crkkx-2AlZZ6OH=rOo_IwqyvM5^Ly{`^!l z6_`WySpon! zWWMR-<;ko#43y#hp%X!=RpKoaq7}qi&6^!cOC-c)SQ;N?JGtYM3y_`7&-dBSDlQCB zLOdN?Y!e>FVu^3wX#B7e_*{z(FaYyh8)J598wF89El|7wgQUpEp8MUNj^LZt)`t%R zyhgaw+oxKPU;#=!qRyVJ+EI|L&?JQH?VB;;#nG0pEiFui0}Gb9`75qLh_>50*Jh7) zhLEE}Ss@{c#Fa8^V9R7$3kNa|C@QMj3b3TJ6uf$pqy9(w@WVyf!+&GJ_SY2ZGDU}P zpw2PgKkew~tecp5Bsy89gf@H?zz|D$?yC0FE9FDP2p}Vt8sVdppVg#|ODrtP*I0t- zH3Txk*2T2sL!j_5pk)Hfed(-(M0$QtnU1Jh7y6ciFQSM<@JY1{4^L3R{%@hNX(KA8 zCSTu8Nz}7lBub|^qF+cuT~pJ-(~}}IL#|3pmh%YK7@;FUqzQ&)K1zsg{uX>*8GOAu zS7(^l(Oc+oP`y(gsX9rQ9aK458@B;ZW)b>&X~aW~md$$na62=X>1Er11p+K8MNvX* zHaU?z=ga07%SvptIPkWL5j*u3k~hMZ zHdd;`9qN$?lmQqucMqq_KzV)Wy0a0*b#?oEtn&i1VHFMn@=d>A+CCnX?%sO$YD98j z(L#UBTJ^BC+kVLxp)u&h6Agg5Er7E)J3A}FVR(7n;?d4o+B_L4qvfm-9}|syFFH|O zb+kUy!nU<^?CCgACg$Nj?w5l$LR!nKpXRN#=n7?t6yqFSv-nLH&(D6*+Sa|S?;?7N z3Hk62`U`HI>LFq;*hfDt8ywNKfge1y7?bh*;~ zOepBfDeMlndM_`<_ADL;AD8r8S~P9EA{v0C?kr`#vG(?xglMr_GqA*BfSgd>1x6lY z!dTwFl_fIj6C{8Y>SlzSHaOy^ukyR)@uiHwZ*JJOkWl^F|JLio2lVd>{%I=#eKE>b zZ;7U#;hIkkX7_(Pc^}PW(KJz9omR>QZ9a8vSBmgjz>q>l?sfo!JAT?vyev0Y+oKK_ z7x(cclYxQZ5zyDKwgBe>l~>veI6t!vb7gCDP1bY!_^>E+Y@iHtT=*aej82oe<3;^J z7y8uy*nAIsK`8K#q(~wn1PwOBp}(V!0)bi8=VeS@@LRi>!G# zYd^fJg2nO=NdZ9)J11Vt^7LBWKd-8eqT*$H%j4}c?$a>QDXVo;Mv%rQBt~w_L;rVcw|v3h zmwk7Kf?Y1dRzM0YnnLPu3LAl0eOf!u&$B{xC6Zgb!N-3#Rhaz#UKkCBRzzb3f6SNA zsUh#5js$&fF{Xyh1-+gg&k;#55OjE(CID%Bk zPg`K%#zz^8ND++*EZhQ3(XWHtu@sK^Sg^3in4hamSHByl7c)KS&k_}Us?fjo4dZmj z4+h24K#*c%sLmFsvy%_ouV9AQ=Msr(f{v8V=;9;VVamn)j2}ot1n}P=_(deb=H^6h zH%wQ~KBGHgUbH?OK1?1(7RWgoF0RGI#4H3DanjAT*Q7;z+SJ7nL`3#@nC@(o(_8+k zBHMU1Jfy5$nEyQ*&>+M9zM>^q7fs2cr<|Dh&I#A23&Kgr3EpC09@DHciaPWg-gtG` zwk~~A$WfONk-fP&9;HtQDNbLo(x3a5byXnt!HoYKr$sKVnkZ}K#;c$SKz+@-kgC$B zKMHUd#BU1diGKZ4*RzFJHBBUCn108iJz$tyDuS%d`_VLYLmo##1LjS2=-m5~*<)qF z_gsl1Cz{uQo==AgrJF1sI0qr-hE!NP;hm3WLsnM;(?MKbLTN ztAVE+rJvga3t;F zy5ZqEQMqA5XO<%5&3weptc=h*s)0PV3O_)OQ)MTIXi_N-)QV;2X9I0J5{T)5^)e#? zJxnJBQI`f;7OBGK8xp{W0@8~3be9~xY_%8E$mv-Y7UZpvSjqvN8 zEAuYCKxPF9-}q5h@I7@BOl!%1u`Ws2;zc@)L=Iv}r|JeR;Tx9P3jBrs7^4pXvjVm$ zON1F9Xa=9#248PITpmh(aFwZ-q_<%lOo-8s&!hp)7@6*iGXY;G(t_s_YZ5$8 zi&1F57=II9Sa2_Q=VzPN@S!2vCMA1&=g=W>pyq4sJg{vFWo2cvY#e~a_dJv>x^&jL zJYN2Hf%cic=y?5~^Ba5tKWG&NaunKOq2@Gg5BE2ytCj@U;A(ATP?^x5m|qfOZ1DK! zF&0#eQ}bk;>|&Nj(j-t$nhp%4S4rM8uq_|?EA>n@v;4KSXy%nA@OpVVcC~h?IdJcf zIiCWmGbsipYcEZ7z5NjubA^4W4iA9x`p=B4n)IbESHlfmjDiuZ)c(tln+V7XEbPRd zRp=KB>6E-?C(F*~X3HBZ)#C~i#2JOk2@-yo>7Xx)tyj_9~709UFPiF&bK`7*e6P4IPhna%|PXZ6}&$5=|WAr1~)2iGqQ!C0~ zRUxEdz*B*42rNi0m_Or|I+_g6qjSz5P9!SO?Xc11ae2FC*LNdtX`x9u>{aY;vM7#) ziq2F8Sh8}I%Fz$De1TX-s4R$0M%V-)!N&Y#{yfm4}SH zNef^cm!Tx66H;*Kd7vbi)ps+;)+L8`9a~dYL%b=Ji;_671UqrP{56`bDUy^-ec}x# zycm)gaC`mV%qwOBjlVzh53m#pPWj)xjL0#OMP8WeQQfl04SLDbgq!O_GMu%>OWc`u zIx+b?u@cvnxK2q=isRJei!t%o6hrwae=PihA-z&w*|NZup5;ZZ`;kJ|MoDDauBvwd zfqj5lG{K^3=2--&x*-9EQJ#BsmJ{@%UWZ6jYbaZ_0`^Zw@5X(MEzJ5?)S|*p?{rh# z81vyTFWWjt4?k2~6c605d4Ds4gNhJCXXoc*qZ#Ueszj;C(Y};OQzpfBlO~CG=Ns4J zq6DsB6;}qr%2IyJuL=bVA(YyU!eICcF>YL;>8h2}ZVb2?u|zMy(^W#BGarRVxvy9BB}$*Y&5IHooEb{H^9rf^?UJ zIG_HGAVm>8vQ7WpEV+OLbCT(?`QktCLW z=@1?Wcy3Shm$qDG@=iBuiN123pe7kleE@KHfB(PN?iA!ldxjhDLwyfGWM-Og3Lr5s zFaSCz-^%=|EK-OMs$Hd14CVvmPEW2!3XoWD+Lm>e6xCHgO<45ZKSSOnMe%I1UlwM8 zZ7(%xtqWo|28L)9LRi3?wyT!EO4kt=D;Ha7uceM}u&}UH*;7vhzKL1@tQU~+xH9mk zt00&hpBh}Wj59}5e=1!QDaG&uKPzK}4Pfc2~w zeQKRbS;`*l`|$(3*ydigaI(PksX9f;pb4bKP3hQIt_%YTnjV4f_{@mgZbY1}1)$Ko z>sAxLK@$4z5Pg95F80shI~XsrOC^tAHVGy%ry~kU0dHojaKOMa6a27o@xU_QiEiGh z9d)z)_`VoqMx*R(vt<-RCsG=H=m*Gg*ck8I8JrfC*&dHW;1PfNqM4R_2j9LEiFC&V zI-3)@LI`R8`$;EdEbDyvmsQwsEv}3OO~(v=wJ7?A9{K&-*@n&h{#+vMzHl(Mr$#io z0}%9b>%#@2`ugNSa>Wz^+k{M4J5P2SI@hir5rGRn!eUiK>$f>Gf2-n+LAB+<`lGnI zTp3FYb97BV+V|%)b|y>yu|E$U%p9U_G;4+?5Xvkod-9|CYwv{=Aqf#{2DGHC3@g_@ zOfZr6ZaquH)N5?^VeaT<0VdGiBpmEBe$Z#%O-x+ktMCxAVn@J86~6!Yp~^639CdrX ziNg2ZUwEVd2Dq#(_w*;~#C4VLPIfXaYXMvXrLKi#c$sFM;4~gqy(7 z(2y?H)}speyB$uy(sWF8t@rq(kn`f? z1&kO=hnbk5aMOB2u4bC%(b$ z?~p1dD<+1ETYO?-J?7_|(=5iO>^8qUoU?^OX;nB(HT&5=T35e&!WRApXhS3A0~L+~ za%?%D9>qT6cy=^9%#89JlcMe}!f$a#vxQ3?Gf2?eG>1buA6KPRxmA>UU8^PPb2CW$ z3%Q?M6FEHG-vNEmjS+XyLTre)V5Ikg4n>zgVzY*e;W+^KdxWPK175~$^>NOq%b_#T zrI|~c-FB9+-r{tHks~1LH?3cNGZu(b2c-%l)lzo!3G3_YYuj^;@c{TmW)hP${;)gX zoD&+Wtlp4@0-`yP`Xe$O0O*#d28qwFKkT|i?l?5?%j*_rr0E>H-?(ULLj#c49jrj2 zl&2PdQ$7F1ML66%Nv;bE)gpd${cFln5j|nP&#y6FkK96(O(?{z*cPdIRj(H9e0`fAeEaWiW$a2xYcf=L>W zb<&HGoSYnZr9{fF-q<-iKSBz{Cnbct6PHkMkM_Uo{x2h8EO0YFk-Q(6%u zh;olAs5uhYy=?{tU7+8aCQ8(3L=-ns*IDdL(5QEepW;tK*cEmi)um#CL?&_Q(B4xq5^5B#(oAV3rI zoV66VDokk^&$8ggYypudG>KeD|`5UnbDxJ9d0q}l;a$NUxzz%akmnx+}~bqQ`8 zfzu=Ecfk=M&Wp()AWHz0K3*X3IL>rwMm_Sd>FLqH=})7aV_FEDR3T(~A-$=}jv^%J z=6ulQfNf)b((I43D5{j0StcGxU7${Y9;U#^yxe;^FBW2oeChurau5N8?GrpyS*NBK zVl5g!0#%~1^!;0tRBP%a$pP96v`1d0YipCd9nn{Dw-=73_i6z&_xfY!va&MA&2O>U zezv~8*`OE+-wsTC#X0cHXiQ7S7)=l z<=dE2@d#>j)stX!v7`_MxzGhm9=9O}K?yjx*%6-1S2IZ5Q4xN8l+wtoPh!p(2xj0N(UV8a`Y*+M?al>A9#!d>k%jubv4Vi-3ma_0f6`&Jb z%4eeqy9Al**Jox(nLhko1KtY6Cm`?zr&k2X*FTc+C}9eYTPagXDm08n$K>F;bb6&N zw7N2@4@8K?5a{wg@nXO&JS-_|0(J_yo#W_}9M#okq6-lJOeo7z* zJ$v@7qs$=GUx@tI)gh2@t zyt=!!m9@;YX3ZM2aPlOKGH1zwhIVN(l&vUNyPJ%8WR|2WI66KjL|~UukN_iLNR20G z^!0AQ;FYbFRm4?y(UB2J1SxRlVQ7<;M1uUw0`eLBFD@~|M*`~HkHBmV`Zsgr9zej& zIxP+U?7CF0oWRX6rT3)qm8cEO;#wat0PKFOM_7K_g^*u80T6Pra(hWZ>*zI zaese*63#N;M}uWeQMfw`OYfHqRT za`TP%(T1;!nK^O&^es)9bEHm);^6ZZYGNIxe3}X&a%~y6y`afU|hd~F-c)-&y%Fy-vts+I1BaM&Z<${cWm3| zhQ6;NQ~=YId1*`Mp9s2*uZlH4_UHo8r2CT#Ob=k>?ZC6VOJR-lA6_8clSgc{v-3f4 ziViAoJ=zW+4FJjdnGEYE!u;CYyyj@w<9%gOTPIBmhjAWC91xSjMuYHK(NgqOpVH!< zM|@f?AXtxlJMhFZZs+!M`ux{pU9Z(%jK2m3HVhw(NC*+%zyHNvkd)Bk$tX$3MhX!o zBm!v`z<2)4^@=lajlgu?^VpC_{}iKSdr#KwGvJl{t?2wZ^&lD#r;oX%)Qv-~lr_=jgZq=RoKg-i?yEC~lkM#h1juBYQv zNJCF+eK_x#cl~?f!w>}iqa5~`(9*<;KW&7Z@nuKM)NWpwam zbOo)I&TC+lP3kueydvNrR?OXZE6>Sp3Wd>iv_!)yB5}?fh zt}ujB4S6*KS8l>ls8~^L)PJvjVc5Sm)NtT zKJOWV;yN8R{L%#tXZCzn`ckQ#c|gc4%b8TcpM+7u^Vq0Jb~EAkSNpV`-CaQZ4mH%M zR9YBJBPai;TrWyCalx<8-N#3$!zHp{uxJJ+ySzsBe7FK~!X4$93W)99-Od@l_`1Sf zd4!N%2M#2X1>CPu-C;hK(azye4tlcI4=DqOu@DNAM*$~fNSGwZF5*N&7G0Lh&-eTv z34qOZuHA!G;S^sb5^Mn3qryH67TbFP9N7q*P+YwMpc#H>xpm(v9akdO5N)CF-tlwP zf0=`(-51JxD@{Hcq{$I52H==cw`pE8nX_I=ib!ajBv#kI*7BsoYcrEbwC0`9el9h& zuBbv1{WW~V6I8Zp&t;#G~(&=W~eo2#s^s1_l+!`61E8B`edJCmiu_?Y>mN| zl~7=B*&FxihHo7lg;Ba3BF^95?k}Fu5iWR94cKJ*cN+U(D4b*b}HN5)`-VYccK0+)QRHr%xp=^=+ zECO8YNcRl?5vc;7Hss%%?=${8{xI~8>HcSG!klL1p&W`bx8m%&kYqq;b!@=1^`}+J_i>pRiLo0=T@Vds%po1)McwzuRIGzJ?)6ieH10LmC5S9#lw1>cW%IHS& zxK%Q=63EeX-}YuT=;Pnz3m(e`pWbRzSX1RgX}|==4@1a5LQ8VO#wvsLa>%olu7>@t zjwz%el#qm^>EA+0e0w7fz)Ae|bs!zbJ)qPm_WMZqYfE!~%jhH#7T{?<{CND41pxSf zv1Ic8iqh5iKS^{-=)F<9j>}2VgSZB=-#uT>nC^>h>DoJBjm21DY7T~)(+&R1dvz$A zdQ=_#+x&g^$a4$eQ35RiFzwR?+!O{HkG>rb9wn}ae9@x+&9k_*M;P#5YmnultC8<< zo~hF%W^Radz`0Q+{WX9h2Ij;Q22Q^Dr!R~HDM6uX0sPtRZ9&RmwTC@4ugTojE|0ee z>YTXwCga`OB~!eTSXdu9rWr+Os(H_|C&|6}Oq%VO;k(5wz|k0B&>r2{`;C9DLmj-UZN`tJ8r{7ABM)SK4?&dG2f$;Tx@hs%G3Xy{^10(_KJlje;8;$xnXV40R&}I zh?o@{Q+ED9O!HdxValkip-ZpbdSJ`}S#R7xk6nGi%w3=f03+XSTn!|@j0{t3z|%LR zQ2C#3xh?x*Tie@xX|HAcM&65gVDJ97l$S^R?#(%LK+qTj@|g9+Jftd9g@q{Uaml0!BvAKXe|?5BT(3 z6?mgxjs|%@9AAr?zCVuhy3fc<4Gj(T3=V#H3B-G{U{Q6JCu@j8IUsMT*|5{#ov+5J zO~V`bFyCm|xOyh^uaajL!Wl4bs+2LSq?_xQ;9CDJ9Q_gObQqvl0r)05i6Jycods1G z?Yt-^A@&h4rL9xY`Q!D*oh}vW=RE1=%D}37JL^Ld$P6AFl&kho9tNm!*MC2syJtKO zL0#=Xj4faNiDQAXnrCY%^fr!yJ_LzCrOzB+ZcPC?5F07xh$kK3Nvk9=y<|&~^YIa7 z`f$01(j)d8|HuqPfL%oi%V=hin!!3=#RINJ`0x)AFuU9+7E&$z<`xEoz*@llIdIFO zj8eXC`qVS1_Xz*9+mnf109@sbmKYItDiRLZ{iqjb1k~@*4M3*@NQm3GxqghBckIyd zYB-5W@RR@^7^8Q*Kyt!|fn(oq#pAD1c&z}laNFaA*MC_kT5aMZgFF=EMn1dNFYMi^ zo0_7m0rW6h@8fA_r-};PtI1s$^6-l@sX&JRJ~0QqoI*qqM%i&2S#8+!iCK9WE!4Zzv`XFeDj z(z9#(UT;_Owq5?&cnla3)|UY5>B@k0P|A6EhGz@>KuX4qhg-Z{_t8>tXi^G7;aXFq zPZ>m{x-&wx)zv9FgKzs^XKBEvUeE(c37;MuxQ>?#UL-m|xGbLHD$%29zDkx|J6Vab z(uY1sGnG%w%7G3xD`>}+(~oSG@fwMwHfeKYH7&Z@glC!hb;ADAYKUs{Nb>!{p7C^F zm9Qr)-~#TokPvl}GG4A-CDv8HTT%3I{5mrbKIPo%0&Cd!BMJqxV7gC7r@z-s`eS$Zp;Nvf`#v}F}En`(;YZPuwng7|J6hD_D zCvYjA?Nd7n>f!RFbYf@|*N`8S=#>@BsQ+}=OAqlOD^bA)o1Y_kAij%TZde1-0; zdPmYyM_76>S}8m!>T=LW&&{1B-~atl0f_P^Pp z)#nw^0W$Ajh{qEq^?v>J$k-OKSFGEw0F+Z81JJK}y_WVB6%}n?M4pZ=x^%z1JBpT7 z7aX4~oG3Hm8sLlPOI+L1n;!Yt75dj7L+wb9RzhUYIRvo`j;yu z`1T87vo&v4YWcD<=xZj z$M2@n^FRQk9oV;Mas_`37BGdUBCaJNAj6>v)A`#p#h`BfGM*T|c74W6pD2mI9u*2d zat*Z`pOf}4x*x6fokf}7vJ_45{uI?2j@6_Gb@+EAb&h=X@fI=>d}7sIkCVkSnEc6-QWDX#6D1hy9 zH}~g{mkwW?`dd&j<6aYc{e#mMkFgguMr(yjd2w=Aq$E%V!QX_>@X05M7}H_tY8$Ev80lodd2%m1 zJMf@|`#Nx7;R*q~YZA|CuH|OYJJTSqV|zBt~R9Nhk`lix4QKpo}eg;{=w#4(fa188s9nleK!vYS+j!6B847`Q?|l z3=It(SWY5XOOb#7k00Jzu`9W3F8gG;R7T{|5{-aR3aUbB7f*Pgj8^4b+=X8DoM?)6 zv$+s8Jx6B`%4n^(&vQK_5=LaWTXbEwySln|pL5PReG9$rnA!95U;Og2f&PK>v$^bm z5aKzzY$KgX!*v|6>fb-wNtII7zE{-V4~v+G7QKN^FWVwyN*R%H77AwjE`lH&RbFjg z-keAz3M*Hx+_`e)%EH2}JZ2`syym_Qlu?f{wxe7Mb%G5;59j@G4k3Jao)_vXRjY)e zn|8&nz-WS|>p8Ia4OG)K_|;jB(U~La>0_J$O4I@fkseR=Zo8Q==G}0^4gX^y*B|ri z^!N9tj~qF2(b(A7D$`7F^*j%Rkf~Z)A!=R{*J#x3R5MCV(_okeTqo3hTEr}V1DzvV zlvJ!O-`4k*OWqtudl#62ql4)qM~+-HIXT%0pf@tYWz4cSPyhg9Y?JT#iEJ)AaK&3M zTUN4@&A`y`sD9|sp-T#dLbsBtmrw#FRjrwN850|*6rsR#GL-~lY<;CtNwu}L9lrR@ z7rnU9Yg-Qd_=TTd?Kn=__x&9JsxxF2C?(*Uw(NJ%MW1GwD_je;Y3#BMA;kA}Lr0-d z*z`Yt^n8nDS;g4(Z45hi?mWN0zyBhx8J-lfmsCfDP{u&2I=+j&3aB0|`yJGETv!PU zgplwJp;UELqJm)>n+c@o=;+vY!37uWUg)(hc7}&X*}%ZS`NPA*>jFQ}xyHBhD1SXI zO%|2tMMJliG4T$X&ZJ?NZD_g%UDx4M9O#A)UDsik?Pn-e=q@0ko9FpEWVN%zG);_+jU$n;py^tuf-fWlL@jMH-{bz8 zjb(43k^ZSuao|)OSP2VK2uw~)!n8~Tz6;LzHbMwSM@KOqZGVL+*El!Y^4flw^EQgM*YWy8sL)iOOo2neP|Vk~!-y^9N_ zAVer46)84E>f*ldgVAtShf)fRg+qtJA5)tFAel^#wzRYi#MMb5d-m*IGd@1vT`rf~ zJlA{1FpXONSt)>0QhN=<`I|Vd0!%4|zz?dm)r+GgtbxQ)+&L58<+l(@1Iw~XEiEmF z+uGU=b+orF3pe=C;r_OXiHXiaq0sHRZW;h0)%IwtN6cvxpF!tLSYOyHg+!@XLb+7N zz`(#}&bh}J6KAYh_0v^7ORJ>twb%Bo8XX;7Q!176hG`Z(&wDQLr^+d#aZQ9^L5AKg zCE^`)jzmS;(ae?Uqy8wR2>jr7A%xC3_i`<{!z)&-*u83HcVS^yJ$nX@4yMcHa;{J) zbeBq{w!jY(06-|&MhJljLKl=$5~fH_*fryG}5pL@J#cO{dd?rlA!r%PKa5meR=BC@Ymp`BJIWR;g6dp64a(lG6rY8vu}L=SQU! zl$5m{a(caU?S+VU&$$x2xN}9*wW(dRI@)hKk@ig_z-^eulY|hsu3H@rB>>=^ue`Dc zlu|(%bvfsrrfD8y%uOT`g=)~s(=^THoO_&emoes1N`uah{Og`|M@Gk)5Q3G<<-Ae~ zK@jLc5E#+FLI_<-$tsmfS}Db<2FH~`@ALt{re#if1~L+T4sSlRI+ZS}{sE@k+T#p1 z=Cp|obdI>rR6{VO6ogH^F_l!cb~sucXAj^wH`p)@P)fH>|5_yBBBjJcVFEz7Lq(0~ zkxLC=)31K%CkVlDp-w3klTtFJ)YeFHvi6V?Qciu$*zp5`2qmC|)~?}HoT@@Ws3lts zyF$t8;6y?~gN)9dl-Bw(;{egzi4Am)M8(|Gch2a|PYA%daop#_p*;kIP*6r7M1a5# zRnDV4AmPMeA$D=+Mr@#SW%`?Xnp%0S*qc+^fgCk$2Yo`kRSjUsT#6Ec-Efwxf5O4*tM-6i(0THCT6J< z8)!^S6B8R~OiU9K8)!^S6B8R~OiU9K8)!^S6B8R~OiUBQ<8tPhn1$q|Ib)A=&hMMA prNqRE!_h|3DF7C-7reJTi{E_=#-Z3ejk7D zb#3yGd!A36xX*o`6Q%K1g_wYb01XX|_?4;>4EVbTe0T70fPZ^B+n0bp_%5mj?r3O) z#^M9t zVV}o(ovF01qghf@Q#t{1BUwjjyN%0!!`Eeh!l~Y03Cb%xbBA-RA;!$|5V66* z!Bz6@ZgQ$BuZqYasp>(#9k6u2du~fw19|y&{RL9AUkf>Scz6;L7?n6!+IS)Qm>67e z`BHRrN(j?*a4-Qg$X;GPyuI(?NAM*<9t8|44}Qdl$m4~;2s8-bHpg$&>FbGr!#FK{=Exi3Ea%;eg&i+g=58+4eZt}!8UC%oP)_6&*0Io+G zdOMx@*&eWG)0(M*SA7`Z90cZPjA;FfL>JuSn6iulP8gL5Xrj7unmzbr3@)I-&r~{w_Crz~2@(P<)XLk;zv~w@|;v0ej$|Pes zKP3vi1NjHm4hKbyWo*fd7X~Y;Fipd%N4}9m6}&%`C*tRgdJsnof*=IK=7G<+!+GvX z5fDx~F1&7&7l*RsTaP9`|KOopmNH4rSGjMohYS8m+{FrhB1F)6=KTCaIlg;P6%m%9 zFR zlLS9R|8=`f&YPt|gdaK_gf~K4W*k)XdWVIV1Ew~?11(xfl}>e6nGgX!!u$hWTSGgX zA01?60~{pM(t$UnZ|wjdy z1&`@2VO+~HS$aG%f3w}_^pYh$Yi@21IU70j7koZLLrbeaQ2siqzhXHv8Q)dPZ8sK>tc}tb$tZ<%e1VQglX~(%=X_fj8rpkL~ zSyj=8Op*@M(GOi#L)#;dZSLw`5@~Pi4rZ&jTp)PZnXkdmf@@D=+;%~qJmu;kA@1p? z*2SS;*xH=Kj)>)NZ^Tbku{ptsAc)d)vbR%HQ~R&jzwfK5y|V6<`;Xb;<`+A;jZmC~ zzmwUsR-e;^gr%h=t?`{VX|T_N$|ww0zN~G!ko{ zeCSo^1j{keJ{}%K6O)iIwECeA%T-Falm{ z`R_2uhEoK(A33ncnOPocYXOnXCVo2Hbl3`w3J+Q6k<6zjd%I+;7P))7yN%!aE&N^& z{_<$(GvRw@SWsXHe3vg<&1?V8PS79x{VVe#?JY_=mV6*rcn|H0@A+m^j)b*9rx|CS zY0^_TXyu*DD~3-i{MC%q*78oT61)IcWDbWXiJBQcU5mQv+?gnFE|1u71pgE(>rWLc zv&BU7@VeZU_Byy*86DLS68A$+5Yt2Oh=@r-V4q!{6NS-K@XmWtVK;~UJ2ghbrgBmt z=MLGMZPo`mg79%QHMI~`($M_;+=)qqKQUUZ)8bsSmg)nW%J} zukAH%`Z(mptcV!*g!!U{S{^;%bvH87^%>B8>45~EZzoCE`t8Vc znPG~ww6vU)fi4Bp-heE!UsdPx57;}^{Q>J33XBDOFm?0^U!p%Bm|6eLGjbI=pR>pR zQYGDCxIEgl4I8d{etv#K^MTf6k?M}eyds5kW-5gg z!%CrGxh1hgUH0%`P@oN69t8%gUv_gL>)7wR&CN|m6$Zib7Nd0%G^^oMNfBUy%gyJP zL)BjUb2a)XQLTwzRMkmD4)Y<%J#1F(z>K|yKr*Z?I_2M-7Q8yNI^gNMMZJOe!e_ml zs(fPNhpald5t*uu6FH-)UVi~*BR=1p!-_c%PfJTvlkk`1&BtA{;} z_49w+zI{e*ZJJ8eZ8+3hR7_FwU!L!V)_*5H*{!Pg(Nv40RP1C?OTa?+zso9nak-C2 zaWs>xoXb7zjBuP^p7WzuOyfNZAD8STXX+-cMZ5bku6h#SsrloB&iHc4<|*W!e=6+E zo-R#Ci+s<{&Tj6hzBhLyX~0o8>f_;3i|u@^<0~OXV@bNKtZZj`dOC6GZrN@D z??|TH)Vp{(&jq+l4HzCN0>(l?!fR(^v;9-daW27jD8{Oxk4oUhlGoocL*HAR+QWs0 zQ_Qfiu%QIoveW8pPF2dS8Qrb57kYJ{Kuk~LhMXN87tcb-W0wUe;WsCP{6T*c44r%` z7S=gM`y-@W|DDDQ`{`2RRaI|v)YS*%G3L{f5*#i!E6Q}v$>-l7?do0GrVIQ839kx3 zQA$tQzV~0)PUJf#aS1jDd0#&U{LL;mz6#0*I%`$E-}g*M6{}Xd#ZawzHS|6aBm#1;6raPOGH~aS_V)Id zbe@x%TD{gcDOA%Lf!7;}b?4_7Awr+6GXgF=j8Pel8%=c&S`B?-PyDwP8GRkMhSTQj z9A>LDxC91&P4|$yq6H_NQ)xr+T!y)IN`ABu4ePOjAnoqP8p>2`c4Vid(tj(6wO$qS zx15a^>Am-{OxbH(iDr2cgMpUrf6`ywb{yke%5{3g9&J!za%o^9CSNB z!Pl_8Miq%0X=){;%KrVgMYRT`ec0-FhMz(9vT+aTSG=&Es`}!-NGm9fe2YbGJ<#KO z?`p#j`dRJx4?}uIR1Iqr@irD_uk8o(*W;u={@Z$d^V#_8g7;@Ngs7yXH_T?zDZ@+* zQK6cj=NhFzMMuD+(_q3pX#Rf~-v;It71>I!`)557T9M+b@8zDuHH`mY8QtM7>y3i#^J}_2t23+wb})!MdwHnbFz#wVMdQ&|}CooxOyP z*PH|W=En09Wh|4ekb&jFw#n2CZ^OcZxtQWrnNo%zc%<>FSjhFY<32{Y%iRsVGTzH8 zj&G9H*5^ETXQ5j^U_7#^4~hP`ZO~j6m4ilx?6GaIu=VhQg!M%!m~HaB?S5#-Pw^vs`>SXD_2vJeoF zr}tMtrZKU%wM~Mt$)O%^!i8U4HjI?j@eta{Ehl@Ewsv_)#r$)Rv!J$v8?YrCPVjg2 z7uPir7K%;g(y!qhcdaUTi86$AM*UJc|@aA#q46`3iSYpOB>>7Qi`k28;OYbfRN zoxA%f;*;vY>Fsih$8HamNpphm0lyQA(MJllzLtz%Dzq?fw0-;S++} z)h>>pqp7*ZIllIhX=VgQ1IGF_3-1GtC#ipMvJSy+ykHt95%p?lkf3B8$nhX+0amXUVNDE@|5&Y>#n?Z2F;$itAr@1C|Lxiu={_*XnJ z>J@m}-`DVfug-hA)WCT-McNO__W7}RU(Xuw4BHe-!4y`qj;2r{E}m$ZIqMqugh^20SGu<|C? zW~;5+UQFE;I<`4TZ*iMkpJ+j^7yqKQyV9SXUn>4d7TZ^^z~z1i#v+T7cryX#kb!rZ zNz{hvl<1~OPnCA_PNYmUJiAzjg6qFaJa>hC7Nx^y{XU#JH8J|V%8it01f?Ou>!HOEl^uGH)bK(}>#~%OqV)AIWn3QPz z>(|iGyOqyqNHiU+F&C`&y%?tyKMUkTI?aRVY!ZgrB30$hX=GOGjQ%9!sNx%=nDe>^ zesGT%w*DOei*_;ibT?lBXVP-ecwqojwMkCkHWh%C&(!|ygci^tUX~))Z){&9ZnEhu zW60Ab_A0taq?=n?1EE9ze}bKa{6@m53=DOQp3V9R;all`P6O9wqyTn`ZE)XeRR$Y4 zBt5O~4VcF_{|aFti=iN!8&ojpPG0`9Vc#Ouo9RY*Vt%ZDc)N7j${Q0Cqt*MP;^5jO zt-)cIvIL!p;gmeTZ(W6+KUxTQ_`f>{xUbRTZaFB-iM1;)qCf6{DHA41MgORC`(V&L zAWDK7;tg}ReGO6VCO_8N{4eR$SF%@|FYx*=|47TtZV8HrgaiZa)0`j2JCY6|XeONy^`8a5#?&nnc(gGfyZA?^T!!#8^AmN0bZE{ z+vVxKSGGz<{t*3GFXN}XgDdlAT_~kM)Hw;N!;t>Jbklg$nPHd^?#+VUcPt#;c=0zR zv5C6(-%;n=LMA+k@*;pBm8~h~vX)ekA$dDjQf?qDn8PXOzC|}ZH9lAM3U!X1!`roy z&GUgR2e#~CoUuGNCuPa?r#!%Ezah~ia8_&Vr^%#)jVW5HAaz8D2Insnwq_|{CEF3` zKt_1BAGtxd^M(cpnSYYB`blpe)|czz-4CGPd+i}R_eF{U>pwRc7@T+iNk;a9BecRk zDMe!gxcBf!uf;v0;_gM=MT0w1-}joU9zzK%52cPk@0AqF$M2Ms0r#Ed#3okWRiq;_ zlX29c-mshX6B(OioIDDKfU_~+sEGW!SKUpb`dAq+WoR3F30%9cWoG=>g~1lDPR(As z{ee)`EwqZn!2(TN9p_b_lM$vQC)cX~@TeDjHQ^T)ARsm*E0~hg4#_PXnFwJlF&zIGjkKB>!TzM2+iLbuD zVV{qCakIUjC-G>p-cU1==Dv82lKm?&+?3Fj$`hJrE(HzA^(+1!`(^ zbo4-i1dqO<6-;j+nUFlr8@4)Hpqj<+kPgF9LtM;J z%Qh85NQc;Xd3jUv)id6ozxuqYi#!rdIgTsSCNjxXKqk(ODfM2ap``dq8+es zI1+SI&8=5jzn*?}BtXrqIyuRd)-ONdS#iJM&;6=m)rET2L97n;iOJro()WDVJs*-g z5&cX!f-FkO`5}2&4i8Q4KUI!O^BEG= zlOsYS?#G$2dfJH0%CCJ|v`X?4+Bkx|SeAZA)C6(OBknA$h~5v&f-UQ-ujH>vIMlBc4k%cS?{$$z2Irnp zaW8g1?TgkNzt?CBh=PZ5%YfdS1?rBR-_@HiXXaw%S-95l2kFVR-gFM~H=T{?i|AhX zPr8{KJWapda4*nn8Y=>VAi2526J|8Gjwjjh$}Tp-&%X_OWz;ikk;szdu(QX#q(`Yk z+U5FH1$De!_vt0K&71_&Plc2>MAQGWGyOpmsLyExq1Z_%jdyV?nGXupW4;cXVQ0|>&VL}b$J^R5n*aWLpO1<_YAwen!cM=69~+}DoUoe zCuhD=#PnM<9d(oGe6Y61Pwc=#jI#mgwsgSYJgFePVWn}e{I+tdu`ucy`DJeIU2a6g zKziIeCl9qS#KTe<`_st1dhb8+D#cWVxXRtwb+!LM_)z9G3AUYHn0Wd!=>>32s$Q#W}IkzHXdd$&+tJUOz@J=_>~4YVu`yrNaaGPh_V zCINzxu?Wap=mru70NEcA}-B3AHr9y=#%L zcwxTLHCMY_d$LoI@ggVLY6hr?JpNG}OH;e$VwTKF*svIG$p9mi-qLQ$NGdKGbGIB& zXQ!=89$2icX2^If^42ZfnW}q{zB4pjonyV%5c!FEpR3hKy_Wd?E2Am^Bh~g{Yc5)CHC=r{+*a|bCru#5eth1&2#q|3* zF+E~D+@}Kyj?b{@BahX;OD(0K-pbkKegc9#t@-s!+y8!9CGg_+5And$Ug?X!J4yio zvN$+61eTD~p^qHyfN4JCW)w3qEiGuGO?4Gvr!`Av2cn420Ws>)uLt+B?eNN6+%~$& z$M_~h&7yoxtw#XKJH5RLW5S9SEEr!DRey2+ClLu;v@}rfzW#pxWJ^QI-;% zXb!5qxU5DZ8DjUCzB4F`(1dR_>H}4qF-nE!%uAjned?a*V@W3(R1I4}21c)%lX~CKIfEA=)pAROMNk3<-ee<96 zhl3JGgEg29K$UcTyohbygzWAC$-(QmyW*R1=kBJ8ZviEji|&VBPK`VBUeDK}zHQ|I z#TW$7!&pUv4rfBNV!^>Ynf>PGwp~(1=E(^D;2}Puut@TGXw1tT7dPE~4NfeS=h(!2 z7{JeViKt1`67%cDTASK{qFn)xCn6$Z($o?@IE@Qmm+*eL-cm35bJl1f1ZIi<{ney@ z8QXl)Bp^12(AX7+9m?!Jly@??^3NfQu$vgKXIb@@PQ(11w)f~8PzWJL(Y8m?As!=C zhG-rPFB}4V02l=DuY7CA660OAASmcd-xvxNslh37aB7&4LH|dBPlnl)8fW;$t;5g! zBtoZE;5Xq349KleP-t>8O>P9#D!`|q&NxuYq(Aq{MKNqa3|Fj z2l9Ijy087v9&j0STRY$CrNW+~@Y^Ep z!GSU-U1%2VZ>y?N(Uz~A0`GsNGRdOCZIibT51rdC=Ij$ySf1E4h9HrA05711VqQfB z4WnN0iBbe3cLJOGfqYatsalYqpTCb7?}?5vQd&27M(Jpp9etx_1;#f2?;rK6K9<8t z{=cAg*t&P%d@xgqDS9jcU#ECSpFoCkZ5P4ewUFPuC^AARP=`GsFat_DiJR@54$iPF zS^&Z!G~r#VkfVO@mE?#wVubURSvyk6G_;lGeX&UllN`onm)rfiWwBI--v1JGi3(s}8`w;XPBoK|A%e@_(ub_F@Ita^1=Pr4 zP#$C7oi<|PyazT40tHp{KF>_o*f;C}s=h_4;3siCS*|1~*NUbbOvQ$c{WPzo>s1RO z{K2YBTAX^bc2^?+bq`Y;3D$<#HecbBJ*Z`g#RqTsUiI(?y1r-Qiz1IwDo0dleDhi} z4|5k#UiDckg%a@p-PyC0dsvNgs^150d17fP)|-c<&$FF6@_Y3+jJy$*8VAB?m`iUv z=c%jnJ+r)xG+GF-^;}rjC^2TbbYP_hR4|nxV!a-)w!)$!@YQ3i z>_I?E0-v$3`}<~^OY;604LoCG?wImY^JJAWJyThx^YIWCY&)2Q5jSSy*Vs zhVt?OWnW)QZQ-CgK^uYO>3yjKz=0U|keYq)Sq(Qax%!77r5lksMMd~;-#!Oa&WK8s zP__1TA!0oA7VbhaU#ak{$NI%-5{kj+jH(YacwJ&u38=0-R~qpkJ#KP>bF|~p?!bHfO9IW^wK|d?&o}h=+OF2V=>0MI zqQs(F5J_l^?akN4^=Lql<%wI#LCeiJ?M5Fw)^cK|av5oSJ6Kb|Yx2>u=f8?5rOvjl zqWHIzJsOkJFNYm5^OSLf`h8YfZ`)`{to*U#Nk-dLln%q4p#zT`F1vfOYwEZsKS zP(ThKQvgONvd!GVL{o;^UGLd8ZRCo#8mZ}MAjZb@n;B9;6LE|;{ou&$$;i~aMB|&7 z@}T=YaoUIwad9UlEq7tMKJ<0EVI{PO-PM`&z^Ed=3BX{GwAtZ4xEk z{?UPmhy>6cXJTb9(EIvF+tG3nF2+>aUfDfsUVPNizDMjn$o_(apV&#PuTLUX2oCITG_hGc;p`g*~Pl9uZhMmG$f zUh@IRLF-h%%06-`ARrK&ziEXx5@u-tFcr0q+sPk)uO%+Ws6NL~#`|`D&IDhn>|>C2 zuS%38j_i8Y9{0eV;JQ)$cJqF>MXr8p`u4ExaeP&qfY~^#SMuieb_|doPyDr!wwaUS zjTXWN0#L#ZVkkJ(cekiqwsE)e^Ao%DFMJJGy@UL1{x5kL6s6LXpOf(}+RWS8rEUpzmWsiTu%o)wxPX6Z=0L|nqQq68O z((}u92*^vnEreKizO7r7`s+jS08&wChsbDzHy0&)+)Zx%-gS0kkF=vt=8uSohzAHt z6~lp1wjF8<1^<^kE48yAcDWR^>~+xg_`sb90|K^L7uq^e>^ej>N?+vN)go*oXY;-= z8YVD&pGi1eaU`7Kb6(Kq{RcC0lV@YSgv!KYq6TH$1VMRtcmggFbJb5*Nu3&|nnlZx zsDe~rA0th1C?sFsUw-#TNM8Xpn>%0r|DJI_J?|9E4f;Uy zlWvEtI4snMz@@wXRFfEa>*Wo?>kD^TXt^tdf(4+f^?cDT)cKC<<{4Mrdw}HE#rR^I zl(j>3cq>Kai98~c#Zd6Y26uu_XSnJlzuT~TL`}1aK_dg_ zr^kTk4t*f{?FVbMSyiWug#92(&hMz=`BhVsCicvFMs-FNo!m(LCn!{d6Y=a;oFkTT z!Sm8leA)k$*l3;nYg{t+%B^PCsz80#;fBh&5mii#8Z`}rGS`nzxrcSR){|z*hRFD(f=<-T-T8(Uk2AQQPa^L#w_`wJ%~5TIWKQuPrq^Xicow>$lt zkugdvisTHmZ}1d&o~DSrUO8O6S-fSae+(&kW*$!L4?fk5fq;kJWMQ=1$Z?_l-Q8~g z@0svXk$Qk#S6tx9`l~&FXrnTAJB~>-{y2LH7~tsaVmMG@ww+)GH%8#7=B?m|0J4(z zc-T7P#fBtVR4^#?(da(I`b|F8#qm>X&bf9GgJQ`4q6LHRcGhd7k@K#xiyawbf{xgW z9GIiCT=9A%Uf+kz=(XP5Mzqel~_p)t7-d&h}GIVa;=!gVfNr3W>z zM!=lXpK#ZVTo2x(duP)fSNse|9vrQK*VWaf-|T%{l4BlFlE&TI`Zsw)&-gr`z0Gxl z)|V@V`hj zsz_@5^Og0=hE&2U=KG+_>qXd~9AK{>80B^gUYr-9f=-SUah=~3lku5+>=D&7a_zb7 z8pD%V|D=>nO-Bc3AYn~qjI9#o>S z`;?B};>_3-{$QA)|ytNj!RYy7QO`Tw-d zW${jCkB=W&;#KAG(2=gWL*ssT2v~&!A;8t>{alQ2+CGA}-<vOl(|~s#2Gz3oYhu+T|fb|21cv zKN|Hr&e4?|OyF(W+|%P}(p;xYb>&o-mmnb<(`Tki*sLXek5pag_|u7DzSZ^g274dIL)S1;y>sXCs_Mn)xbuPIPO!2s41?(|`h^ zlBK~{7z<5I=MS>``+Et;v24Bk(5cH7x78l1MUVBmR?qu`*u_umYXE|tbRkG`cp7hm zRcmPm$k2slC1J=N7g;YO(a&7y!#-oo?_bW2^$Gvb!vKiGbkJ`r;c(yb>*!~R*S8bt zOE2D}Oh=QyI0`}iufDymEBC){O0^#bG}48!$w`0~L`S)=0@U{yHJPX=H4Pos%HtyG zONV2N-Xr0uruRQ|`Ily!?A=ha})de{|`zc+r!Y7{jesV_qU;gnbp?=_hk0Qy_lJw_TOCU-m9 z-YSUqn%HK)1KU|S+SwKF&S&)AC%+0d0n25?*(I~*!hXsHJ=k|d-z+tF@34u#4>+F^ zm#U4~w4J!)p+|vBKYSRonHniw&ua8KeF@EBs7}Wvr4^=p{bTLvylE0=CSQ3?s9o$dKF@ zE|;Oe^IS-M?BOrH0h9CrnqsWaEx(mx<-LeYVhS(4m6 z$`j+$z!x#@-VGLLeV(AG9wtOLhq~-}4I_^3vSP1~N&U*fWBqY2?JX|ulk&2cK-hM6 z=HK1j%|viry;n>|ANhFKi3U-~>8X1|7XyzG|JpyDQJZmHxh`uNQ z`WyjVtPE;!BWJk#_)zZQ95?8!D=yLRzo~(?fQ`Xr;z-t_yhI~6lK@58wJ5Cdt}be5 zUOTno>(|^jH#hQl3L<*p+2dJ=0Zi;55F{9L`y+I?bkeyHyRQ;mxm~o4{*$G_?{`mG zj;ZT=UDsZ5;8eDfw_A_g{=FApb~{x=t~1#ipq-|;`XD2-CP8a8qOJGAH%}~nkmPAo zXzjQ_KkK~0E*5N~BQyuNziccdXw;J)=)8C7{_n*8%^Ml@Gw2OmtRWrxR{{nKt)3s(A#bJVE(O>0!F0XGf6&p4qed z|CwLV{W+=t27XS4zug!cZQFT@l?w|j%;vGDIcHV?_k7;T5oGJ(k|F(w%n=_lppr$s zlpyQn*b1uR`jVnUVDhl5*XnnZZNFXgQr!+*m{yj z{Mg`~PZ<6hoi2^|Zwi-dySr9HSF5)IE*|_2TfBU{^u#|LOElizDBo2St-6sOe$|M6 zUji$=&cp#f&;9CmPBJACnX=cn=F3MG1*}lN!c>82@>Mrg>sb%wa@+ldrJ|zZzpAsO zL=mt(J9~TP@Z}HVCeJkMW3>cc*!rJHOBkVuU1Q>?f1Whd<+!TdBLggMdX!bXt;>B-a-4WT)SLIH#iP{H6fOGR7^Q>k2ruhCKTEM_BrQ@ut4ccbQk22jcS8b>hEEVuV=$qyQ zb809#0*=DUmmXIzPX}fG1Y;hB^9Q(Mn;QX1a>GlMo%Tr#nT3!oQ64NXXy(n+t|AH% z@p2R{!~X8>_!pmLB?vzHIuU?H{`eOsSaysO^BC11{V?4z^hpis zxb|9h8!Q_H6afuGtuSw%hyx^_1_WraTB(1#QUCFzvg43hBKxPTJ9Ke-px1i00w~8CdU~X4sL|!+ zI3*cPRqIma&o|nTPgQwT^h7>#TzNz=C?H~MaKb0vO7nv3C|!oFAI~E%mxCUwI*hVv zvN{w1&O;&$^xg+o97k4G7JEOMFUN32qsb{EQn>%ak{722)(X6{#z7UuJ(*0uuQEg> za|(}i5y8=errzwRw|NA8mDLhWy$mNjXg&9<>W* zNES1oKnst^oVGDut%h|l)C@>GhMpd_o=+e0RlgxLrD)7IcLC_#t?((GWqG*|l@b!x zD+`A|-@kR3=bOXOMPy8g3{`#BneYhy7Rsmtm1ES2i;(9f96ujz^%DoQ`Y=-e70mLb z%l3Q10m-G{an}dztz|X5CxZ#buIh>bn4PNvur9EYyYXK;J2Dr#0vF*prEGzglO#i- zq&ESThrD)Hp2l^h7p|QMx;|aaFum8s8t)q~znXu9+am^eKw8ee7jotg}m0s|{MOKDH+CZ_vTXRKZz$QhP?A%IK(vPS?M~nUw(N{0uAs!h-CE=EAaQp%om&N@7eKq`9kMH@LI)YBSQ@^BfvnJR98VT*_J>c^WdO6~(A zWjypOtksGP*SsAmqD6VJ?@34fRx$~unOCyhMkwCbAS)4?mq5IbpzAe78g1-+Q4azO zuw(!I|Ghn4%Pkw&S*ZmLDuHouam}Q~zQy#Xk;|s9uCCrR6Bbc_PB)NMN3i`|K9#`( zS335Q{Ac6X(-}^PnT135)m_f(;GX-S`LyccA<)HGrHUC}*gk>HLQFRGZ7b>|CkG5I zg>iu}9Oi3tDz}BHqPBcA;F$onVZ0lS4DCJ+7Q9}#&S<(EmOgwpJwH#V{%UdxW#%m* zn}u?6c9t8gBL&EQYh9q1Sx*nuoIPUn+!uK|V_=Lty zyRfWmRycm^aAzl}XlE|@SU=|r-yQ_qbL7&9{P%hoK>`2!yOT7zdiyb@4C&0O{z&#E z|5LAnS9uW}9#-@;G|9cxVSBzzzv}Z`G(Y4`l5WuSoiuR*jjgla*j@+ThcVtUf$Zcp zQ!lSi4=khmqn4`YYUxj8oQ;yfu+qSC>aNkDGQ&FYku;#`=!%(61|XHOAjH)CTY(1) zw;U(_4fkB+>Hmfucwa7a_w0Xs7FmF%{)y_+!;}8~q#y=HK3>zu!xzfvdr4;PZeN@q zHGkQ19rAM}wuv%j!YUl49Sp?~7*`S>zJIC3*>a`lSeROr-XSc+#zFu%IVbyf-l5Is z(vIg@w(pRTFuT3|{WQsgcq}Y!X2ZIDo2L)~W0bazU=*ehRyFJJ!K0i_ELN!KWy^%uqIV#Q zyGS1INzmd^9qSi{m-6zIRpwhr-=Om-hVB+@vlw!rPeE1;D>us@U4&-#j=-tVfVon zY7 zt8|fvPG6jzVO4gbYkiB2jRocp9K$(IK3EbZII7Eq)o-)(AeQMqyE!7&K#*~Fcf z7GP(E7#Lh%4-T9bT~oh)B@=Si9&jWzM!i&>P+*q|wdKi0>|OqyC4ZiW`v&~+?~H3I z%+9zd)})HhZO5b0X(U~C!*P}pBoK0TcJ?2iC4bttPd`8yT>{e%i;d^GFgiIV)2id$ zlJfLi+hoZlk$SJ3=O2b>(_uy0ZYZR&!dE4E9pKE$NQsDk*(6Wvx_-b8b`bjlbS~w$ zwA}xMrLi)Z3RM82&ANxNiQz7ZC)<+}Q0JlQTQHD+787_4L*=7_i*u{1g=HipW>VwU zXw}z?Dmj0MQXhNM0TD9wv^GuJi$U-6DHawY<>KOE9qrd_ZH$YA(YVzR@GKYw!uCi8 zn;CsTNWd|gH+t#Znq zuK+~37;=Sc*~w`Xkv z`kK?u-kv==r-(5(kJl-x7DmvR6<5MEr;l*33J}lL7KnD4KRR+bDXUvbHjWjvn4m=#$5AhC4qW7 z-m}0(c7;rej*{|Ln&-v1Z@3;#65Hsu8d)rorwvEQns9<8LFC*^3nm(N*g>@5-`Xsz!i6;7{lxWv{@WWpBkZAY9$)98wU;ssRnL57d(~ zCX}mLb#_jFhZMxdLTgWPc9NllmwM4t!LN+T**NJ6{9l`98X;*%Ue1iJ{4_wDkuFo! zY(DCAR_E`l$G~_WcumT93LljnIaRd8583izf-*VSe0^^#Y`+v!1(ci+T2wtbo|tL& z^+d*lKZN~z8Rn?iCVyf`Kd0_YLdz1~v(2EkvnKUKKOS_gu(rF6n01`{d^`I=*#t~M za8L0+3ExN4`}6%FqX{vD3==xAIb`?_Xpu-RK)frU{a*L8KbN9}qLVav^q1$(s>7mv z`TYjmEe@P1HCyYbvJRYr`e!9pd!Ua$?PUK|-v_tPKLoZTNQCV%+8aYUIyT!L1Kd}_ zh$V9WO>8YSU+)L4(3tGah*4XA1qK2!+MiRFAnlKGGpP1vNF=uQK6-i3on8*5V07Tn zkpXaW#^mAT#k$x zcZ+08uHB}fTSTO!s0QS1HU-(S5}nmF&U&7` zw-J;JR*Ha0q{D~7(O=Q$t56?59$a&%H{O^DTRYm=6}LWPS!p?LD}UJeGdT(jMa?R^ zQHs&ehvnOT9pJt^`kYNx)-igzFM$Y(6oKG)82i~}I&Z5xJ6!D*G&MFBFV&D&1pN!k z%Xb%T>a^R8Ht5WbtEv)ur>_+zMB8MX!eQ~kB`)-TsD#4XWSKLg(Fh!!n~yiw^7Ccq z)g@NpF&i}I?cJxFDbB<5Q%kON6IaRp^H2L+-D-*{jZn(ZN~)q$KBpS=LBLbf6BFXM zq(N6*DuB;T>mM9rA<`4y`|eCGHc7=r0WJuPmcTUQh4=IYhF7GV=G#ZnfFVEAWGg={ zt%(Z@A%i5V_F&AD8iDK!=aIM62|g~irnMd-r0GT28=tE|L}`O?>XJgc<_d?e=qu?oMSKC#r~#`Cs#Xyb@j6tOA9ci zr~C356Lv0HW^~9d1ypFJ_CDKj{!7r~?Q&36R+iZ%Ae%PjEtnHac>mjXz2#s6X~*H? zyqL@%FLy#)WMz z-L%Ql6WnH6dV2cGx+UMeoLPrj_NQOUKEiQ>S>Eem&R3aQ8*ew_^nDj#VaBVIx-0{h zmq(GSjmBxim!k9v8%%-a39xWP6C$XOo}O8CbzZNWot^z&zaGp7dX-W(=zZF40DLNMgnD>4Gr!VU3!5$9(2yFazQ&!pSefc9|k7_UA34A zKO=<0sI%}8F#FrvNP*O0zJ-aY2_4}2guRB%bP}mGZ0|g~mSg|^-IjrYYZB}MIyM{@ z{N%Gd6rTWNfSL)IZKg&?!`61qH}U-JN%VVr6cDoW;O5dmNlii5cU@s=Z62kR?WO#B zPh%EG^5yJNop{_rLjcMZ4zi&Mf=&=~=B;cr))jH7Z}^Gl=j#{A9Rf{$KN-ha;Bd=# zE)H8kkvNecf=hmCI#o{*F)=4+C#dcgyA9bt9Or7}tbXV)P-qU1E}%Z0K&SuTbof}Y zXFnYez?DM5@?g$y?uRZUAau5SC;|K*XH3OA(b?YKe%IRCy4Y_~)lyW+4BBVjjA?82 zdE=#rasX4Brr3FeZWS`Lt|shq~J7Xf}>F| z5tyci+0#Mraw8|&Xx|d&00oAbIxuSh_$V@AXK2SQu5EnwXtS49`lA;eJ{mAoR)Pox zwU!M1mu&jqp+KQv+gv7)Wa07?HC19Fd>p{KThB+isaY>>PJr}#qZTEihWQU_b_$i9 zr=_I<%~u)AH3d0sNFK--vCWZyEHh1yyW+9?D#ebJZ2C~p@9raCIHAQw}V2f_&*J9y=s5F z3<`S8UTpHR1|~4P#KpvFab5dxttRr-gn=NmIa5oYhp2sN?phy92w*xys2TOAo-R;2 z?)=9U)bV*8YjpL3Sh&15My;h{N_S1b>wW}9$=2q(=YK9ruVo#U-Z=cZNmDHX=%Lll z)rO7Atz;&6X|*G5)5rbJgT*GQzV+j!-rn9c_bpu$*}@Mq%|7n0t*y7>0Yv-EJoZ0N z5N@yoJ0TPtZL}&54p?VcDfh)2!mi@PW@CdRm=G+>k@?91MTflziancUH8cEFKcGBQ zk3N%Trf66&z-Bha!$+gI)}hIwLz|13Fd!=M;#q2R#Ff~3>*(mH_b+%ARkiK!>{~A` zE>;7x_XSD$Nxx+maXJZtghBFLf83w}Pd59#$}~VTC0x6OhnB^kMMfqm>~}aPv-b}V zRh*p<*8pdK4fLjI8yhdC=fp{U@O#$x@%R4)Ndvb0+5Gm_mb^HH5KJkxe(ZMz6iXo1 z5@4AYD5ao`wgG@?n#g9ei+1nceWX%~CF1ekL?Y3XOeWit$@+?!F1Bsk(U?l5l7mA- z%}OaIrDRgdb$OQ;kn>&B$}C7W*$Kp20-~`fgb?sNuV5?zu#OM{LV#>Gi%cei&d$z- zgb)~pk%`CS{k65VT{C91ls#&yr>BpZrdg9prIP7%y56#^Xl~|YN}XyN=YEr5@2Rc^M%?bzMzL$pAnIp*xNf z&OdD14tcH@7D6y1WTf*;+R-gHe1jZ8JRC3Fj6B!Nz2wiRgaor{sR+bc0(3)%loC=1 zNFgDG^z9^Mq#C1?5>m>%Xh8^pByz1%3N#lEDW&w6(3uS6sHNsU5j>0k_P4)*5Hi+s zdR_hp;f?$%r38f1QEn1eSjLZx4F$_Nr8M6+7nJ(%$y?N=5b!)PWh0DAO(511;N)gb z$|%?<;VCJ7(NO{=a}W3$_8$y{0FG_>@6UCRBb0)(5mAq}iYlerfLt_I4k=Y(hAT{T zh5wU6V8J^YRw)IgfN(gn*XL2nAHVPtf9>BQYXM->0Y`M>`bv zqrcI6#Zmu^&3oK8zC&C@<$R(3#h@S{$$c}-50dUR{jYeTve)P<~hT+lgrz+5RKtQobGAfUE spVx>2gz^xHM372l{7NOEP#OUKKjY`LOo*q}c>n+a07*qoM6N<$f